Skip to content

Commit

Permalink
fix(velodyne): velodyne fov settings (#40)
Browse files Browse the repository at this point in the history
* decoders. add elevation, fix point attribute calculation

Signed-off-by: amc-nu <abraham.monrroy@gmail.com>

* velodyne decoders. fix azimuth and ts

Signed-off-by: amc-nu <abraham.monrroy@gmail.com>

* cspell. fix typos for ci

Signed-off-by: amc-nu <abraham.monrroy@gmail.com>

* tests. update tests pcd to match new decoding

Signed-off-by: amc-nu <abraham.monrroy@gmail.com>

* feat: add view direction parameter for Velodyne

Signed-off-by: David Wong <david.wong@tier4.jp>

* fix: change view direcction parameter to radians

Signed-off-by: David Wong <david.wong@tier4.jp>

* fix: timestamping for empty clouds with limited view angle settings

Signed-off-by: David Wong <david.wong@tier4.jp>

* fix: ensure that full 360 degree scans are rendered, and configuration parameters are used correctly

Signed-off-by: David Wong <david.wong@tier4.jp>

---------

Signed-off-by: amc-nu <abraham.monrroy@gmail.com>
Signed-off-by: David Wong <david.wong@tier4.jp>
Co-authored-by: amc-nu <abraham.monrroy@gmail.com>
  • Loading branch information
drwnz and amc-nu authored Jul 28, 2023
1 parent 09805ef commit f106371
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -216,21 +216,31 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig(

target_key = "config.fov.start";
auto current_cloud_min_angle = tree.get<std::uint16_t>(target_key);
if (sensor_configuration->cloud_min_angle != current_cloud_min_angle) {
SetFovStartAsync(sensor_configuration->cloud_min_angle);
int setting_cloud_min_angle = sensor_configuration->cloud_min_angle;
// Velodyne only allows a maximum of 359 in the setting
if (setting_cloud_min_angle == 360) {
setting_cloud_min_angle = 359;
}
if (setting_cloud_min_angle != current_cloud_min_angle) {
SetFovStartAsync(setting_cloud_min_angle);
std::cout << "VelodyneHwInterface::parse_json(" << target_key
<< "): " << current_cloud_min_angle << std::endl;
std::cout << "sensor_configuration->cloud_min_angle: " << sensor_configuration->cloud_min_angle
std::cout << "sensor_configuration->cloud_min_angle: " << setting_cloud_min_angle
<< std::endl;
}

target_key = "config.fov.end";
auto current_cloud_max_angle = tree.get<std::uint16_t>(target_key);
if (sensor_configuration->cloud_max_angle != current_cloud_max_angle) {
SetFovEndAsync(sensor_configuration->cloud_max_angle);
int setting_cloud_max_angle = sensor_configuration->cloud_max_angle;
// Velodyne only allows a maximum of 359 in the setting
if (setting_cloud_max_angle == 360) {
setting_cloud_max_angle = 359;
}
if (setting_cloud_max_angle != current_cloud_max_angle) {
SetFovEndAsync(setting_cloud_max_angle);
std::cout << "VelodyneHwInterface::parse_json(" << target_key
<< "): " << current_cloud_max_angle << std::endl;
std::cout << "sensor_configuration->cloud_max_angle: " << sensor_configuration->cloud_max_angle
std::cout << "sensor_configuration->cloud_max_angle: " << setting_cloud_max_angle
<< std::endl;
}

Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/launch/velodyne_launch_all_hw.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<arg name="packet_mtu_size" default="1500" description="Packet MTU size"/>
<arg name="rotation_speed" default="600" description="Motor RPM, the sensor's internal spin rate."/>
<arg name="cloud_min_angle" default="0" description="Field of View, start degrees."/>
<arg name="cloud_max_angle" default="359" description="Field of View, end degrees."/>
<arg name="cloud_max_angle" default="360" description="Field of View, end degrees."/>
<arg name="diag_span" default="1000" description="milliseconds"/>

<arg name="setup_sensor" default="True" description="Enable sensor setup on hw-driver."/>
Expand Down
12 changes: 6 additions & 6 deletions nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,15 +195,15 @@ Status VelodyneDriverRosWrapper::GetParameters(
this->declare_parameter<double>("view_direction", 0., descriptor);
view_direction = this->get_parameter("view_direction").as_double();
}
double view_width = 360 * M_PI / 180;
double view_width = 2.0 * M_PI;
{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
descriptor.read_only = false;
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
this->declare_parameter<double>("view_width", 300., descriptor);
view_width = this->get_parameter("view_width").as_double() * M_PI / 180;
this->declare_parameter<double>("view_width", 2.0 * M_PI, descriptor);
view_width = this->get_parameter("view_width").as_double();
}

if (sensor_configuration.sensor_model != nebula::drivers::SensorModel::VELODYNE_HDL64) {
Expand All @@ -214,7 +214,7 @@ Status VelodyneDriverRosWrapper::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 @@ -226,9 +226,9 @@ Status VelodyneDriverRosWrapper::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();
}
} else {
Expand Down
6 changes: 3 additions & 3 deletions nebula_ros/src/velodyne/velodyne_hw_interface_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ Status VelodyneHwInterfaceRosWrapper::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 @@ -192,9 +192,9 @@ Status VelodyneHwInterfaceRosWrapper::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

0 comments on commit f106371

Please sign in to comment.