Skip to content

Commit

Permalink
Re-added missing DVL plugin ranges topic advertisement
Browse files Browse the repository at this point in the history
  • Loading branch information
dtdavi1 committed Sep 21, 2021
1 parent bbf5e5b commit a3a2c57
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion src/dsros_dvl_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ void dsrosRosDvlSensor::Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_) {
node = new ros::NodeHandle(this->robot_namespace);

dvl_data_publisher = node->advertise<ds_sensor_msgs::Dvl>(topic_name, 1);
rng_publisher = node->advertise<ds_sensor_msgs::Ranges3D>(ranges_topic_name, 1);
pt_data_publisher = node->advertise<sensor_msgs::PointCloud>(topic_name + "_cloud", 1);
current_profile_publisher = node->advertise<ds_sensor_msgs::Adcp>(topic_name + "_current", 1);
pt_data_publisher = node->advertise<sensor_msgs::PointCloud>(topic_name + "_cloud", 1);
Expand Down Expand Up @@ -468,7 +469,7 @@ bool dsrosRosDvlSensor::LoadParameters() {
}
else
{
ranges_topic_name = "/ranges";
ranges_topic_name = "/dvl_ranges";
ROS_WARN_STREAM("missing <rangesTopicName>, set to /namespace/default: " << ranges_topic_name);
}

Expand Down

0 comments on commit a3a2c57

Please sign in to comment.