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: /tf and /static_tf topics' inconsistencies #2676

Merged
Merged
2 changes: 2 additions & 0 deletions realsense2_camera/launch/rs_intra_process_demo_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@
{'name': 'enable_gyro', 'default': 'false', 'description': "enable gyro stream"},
{'name': 'enable_accel', 'default': 'false', 'description': "enable accel stream"},
{'name': 'intra_process_comms', 'default': 'true', 'description': "enable intra-process communication"},
{'name': 'publish_tf', 'default': 'true', 'description': 'enable/disable publishing tf'},
{'name': 'tf_publish_rate', 'default': '0.0', 'description': 'Rate of publishing static_tf'},
]

def declare_configurable_parameters(parameters):
Expand Down
1 change: 1 addition & 0 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
{'name': 'initial_reset', 'default': 'false', 'description': "''"},
{'name': 'allow_no_texture_points', 'default': 'false', 'description': "''"},
{'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''},
{'name': 'publish_tf', 'default': 'true', 'description': 'enable/disable publishing tf'},
Copy link
Contributor

@SamerKhshiboun SamerKhshiboun Apr 12, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would prefer to explain more in the description field, specially for these two parameters since they can confuse users.

  • publish_tf: [bool] enable/disable publishing static or dynamic TF
  • tf_publish_rate: [double] rate in HZ for publishing dynamic TF

Also, I would prefer to explanation and elaborate more in the README.md file, where we explain about publish_rate and tf_publish_rate
1- to explain that publish_tf:=false will not publish any static/dynamic TFs, even if tf_publish_rate is bigger than 0.0
2- to explain that publish_tf:=true, will automatically publish static TFs. If dynamic TFs are needed, user should set the tf_publish_rate for it, and it should be > 0.0
3- to mention that the default value is publish_tf:=true with tf_publish_rate:=0.0 which means publishing static TFs as default behavior.

{'name': 'tf_publish_rate', 'default': '0.0', 'description': 'Rate of publishing static_tf'},
{'name': 'diagnostics_period', 'default': '0.0', 'description': 'Rate of publishing diagnostics. 0=Disabled'},
{'name': 'decimation_filter.enable', 'default': 'false', 'description': 'Rate of publishing static_tf'},
Expand Down
17 changes: 16 additions & 1 deletion realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -984,12 +984,17 @@ void BaseRealSenseNode::publishStaticTransforms(std::vector<rs2::stream_profile>

void BaseRealSenseNode::startDynamicTf()
{
if (!_publish_tf)
{
ROS_WARN("Since the param 'publish_tf' is set to 'false',"
"the value set on the param 'tf_publish_rate' won't have any effect");
return;
}
if (_tf_publish_rate > 0)
{
ROS_WARN("Publishing dynamic camera transforms (/tf) at %g Hz", _tf_publish_rate);
if (!_tf_t)
{
_dynamic_tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(_node);
_tf_t = std::make_shared<std::thread>([this]()
{
publishDynamicTransforms();
Expand All @@ -1003,12 +1008,22 @@ void BaseRealSenseNode::startDynamicTf()
_tf_t->join();
_tf_t.reset();
_dynamic_tf_broadcaster.reset();
ROS_WARN("Stopped publishing dynamic camera transforms (/tf)");
}
else
{
ROS_WARN("Currently not publishing dynamic camera transforms (/tf)");
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just a question, can you remind me when we will get to here ? In which scenario ?

}
}
}

void BaseRealSenseNode::publishDynamicTransforms()
{
if (!_dynamic_tf_broadcaster)
{
_dynamic_tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(_node);
}

// Publish transforms for the cameras
std::unique_lock<std::mutex> lock(_publish_dynamic_tf_mutex);
while (rclcpp::ok() && _is_running && _tf_publish_rate > 0)
Expand Down
1 change: 0 additions & 1 deletion realsense2_camera/src/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ void BaseRealSenseNode::getParameters()
startDynamicTf();
});
_parameters_names.push_back(param_name);
startDynamicTf();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this change the behavior from default start publishing to not?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When the node is started, "startDynamicTf()" is getting called twice. So, the prints are also coming twice as shown below:
image

With this change, it will be called only once.

Basic testing is done. Will test for corner cases as well.


param_name = std::string("diagnostics_period");
_diagnostics_period = _parameters->setParam<double>(param_name, DIAGNOSTICS_PERIOD);
Expand Down