diff --git a/nebula_ros/config/velodyne/VLP32.yaml b/nebula_ros/config/velodyne/VLP32.yaml index 3ab79e2b8..ef5ae14c1 100644 --- a/nebula_ros/config/velodyne/VLP32.yaml +++ b/nebula_ros/config/velodyne/VLP32.yaml @@ -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 diff --git a/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp index 2f28f01d5..172e61c83 100644 --- a/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp @@ -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("cloud_min_angle", 0, descriptor); sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); @@ -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("cloud_max_angle", 359, descriptor); + this->declare_parameter("cloud_max_angle", 360, descriptor); sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); }