Skip to content

Commit

Permalink
Leave empty tf_prefix values unset
Browse files Browse the repository at this point in the history
As reported in #554, tf_prefix has been long deprecated,
so if it is unset, leave it empty instead of giving
a default value.

Fixes #554.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Aug 11, 2020
1 parent 589a52a commit b8b8726
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 12 deletions.
4 changes: 0 additions & 4 deletions gazebo_plugins/src/gazebo_ros_camera_utils.cpp
Expand Up @@ -295,10 +295,6 @@ void GazeboRosCameraUtils::LoadThread()

// resolve tf prefix
this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
if(this->tf_prefix_.empty()) {
this->tf_prefix_ = this->robot_namespace_;
boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
}
this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);

ROS_INFO_NAMED("camera_utils", "Camera Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
Expand Down
4 changes: 0 additions & 4 deletions gazebo_plugins/src/gazebo_ros_gpu_laser.cpp
Expand Up @@ -132,10 +132,6 @@ void GazeboRosLaser::LoadThread()
this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);

this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
if(this->tf_prefix_.empty()) {
this->tf_prefix_ = this->robot_namespace_;
boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
}
ROS_INFO_NAMED("gpu_laser", "GPU Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
this->robot_namespace_.c_str(), this->tf_prefix_.c_str());

Expand Down
4 changes: 0 additions & 4 deletions gazebo_plugins/src/gazebo_ros_laser.cpp
Expand Up @@ -129,10 +129,6 @@ void GazeboRosLaser::LoadThread()
this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);

this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
if(this->tf_prefix_.empty()) {
this->tf_prefix_ = this->robot_namespace_;
boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
}
ROS_INFO_NAMED("laser", "Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
this->robot_namespace_.c_str(), this->tf_prefix_.c_str());

Expand Down

0 comments on commit b8b8726

Please sign in to comment.