Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(velodyne_hw_monitor): allow max cloud angle of 360 degrees #50

Merged
merged 1 commit into from
Aug 10, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 5 additions & 20 deletions nebula_ros/config/velodyne/VLP32.yaml
Original file line number Diff line number Diff line change
@@ -1,25 +1,10 @@
#nebula_velodyne_hw_interface:
#nebula_velodyne_hw_monitor:
/**:
ros__parameters:
sensor_model: "VLP32" # See readme for supported models
sensor_ip: "192.168.1.201" # Lidar Sensor IP
host_ip: "255.255.255.255" # Broadcast IP from Sensor
sensor_model: "VLP32"
sensor_ip: "192.168.1.201"
host_ip: "255.255.255.255"
frame_id: "velodyne"
data_port: 2368 # LiDAR Data Port
gnss_port: 2369 # LiDAR GNSS Port
return_mode: "Dual" # See readme for supported return modes
scan_phase: 0.0 # Angle where scans begin (degrees, [0.,360.]
packet_mtu_size: 1500 # Packet MTU size
rotation_speed: 600 # Motor RPM, the sensor's internal spin rate.
cloud_min_angle: 0 # Field of View, start degrees.
cloud_max_angle: 359 # Field of View, end degrees.
diag_span: 1000 # milliseconds
advanced_diagnostics: False # original diag
min_range: 0.3
max_range: 300.0
view_width: 360.0
calibration_file: "./install/nebula_decoders/share/nebula_decoders/calibration/velodyne/VLP32.yaml"
data_port: 2368
gnss_port: 2369
setup_sensor: True

online: True
6 changes: 3 additions & 3 deletions nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@ Status VelodyneHwMonitorRosWrapper::GetParameters(
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
rcl_interfaces::msg::IntegerRange range;
range.set__from_value(0).set__to_value(359).set__step(1);
range.set__from_value(0).set__to_value(360).set__step(1);
descriptor.integer_range = {range};
this->declare_parameter<uint16_t>("cloud_min_angle", 0, descriptor);
sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int();
Expand All @@ -278,9 +278,9 @@ Status VelodyneHwMonitorRosWrapper::GetParameters(
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
rcl_interfaces::msg::IntegerRange range;
range.set__from_value(0).set__to_value(359).set__step(1);
range.set__from_value(0).set__to_value(360).set__step(1);
descriptor.integer_range = {range};
this->declare_parameter<uint16_t>("cloud_max_angle", 359, descriptor);
this->declare_parameter<uint16_t>("cloud_max_angle", 360, descriptor);
sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int();
}

Expand Down
Loading