luxonis / depthai-ros

Official ROS Driver for DepthAI Sensors.
MIT License
239 stars 173 forks source link

[FIX] fix optional passing of Oak TFs to be truly optional, necessary… #473

Closed hollydinkel closed 6 months ago

hollydinkel commented 6 months ago

… for multi-robot/multi-sensor systems

Overview

Author: Holly Dinkel

Issue

Issue link (if present): #472 Issue description: Launching camera.launch in a multi-robot/multi-sensor system leads to system failures

Changes

ROS distro: Noetic List of changes: camera.launch

Testing

Hardware used: ABB IRB120 robot + Oak-D Pro

Visuals from testing

These are documented in the Issue (#472).

Serafadam commented 6 months ago

Thanks for the PR!

peci1 commented 5 months ago

@Serafadam DO NOT MAKE A NOETIC RELEASE WITHTOUT FIXING THIS!

No, this can't be right! This solution fixes one problem but creates another.

The only thing this PR did was invert the condition whether to include urdf.launch or not. The group additions is irrelevant.

With the inverted condition, we have now:

pass_tf_args_as_params:=false:

1) urdf.launch is not included 2) camera_i_publish_tf_from_calibration is false, so the driver also doesn't publish TF. 3) Thus nobody publishes the TF.

pass_tf_args_as_params:=true:

1) urdf.launch is included, sets /robot_description and publishes TF via the running robot_state_publisher. 2) camera_i_publish_tf_from_calibration is true, so <camera_name>/robot_description is set and TF is published by the driver 3) The static transforms are published two times, once nominal, once calibrated. What gets used by TF clients is random, depending on which message they get last.

I think a proper solution would be to invert this line:

<param name="$(arg name)/camera_i_publish_tf_from_calibration" value="$(arg pass_tf_args_as_params)"/>

If done, this would be the result:

pass_tf_args_as_params:=false:

TF is published by driver, <camera_name>/robot_description is set.

pass_tf_args_as_params:=true:

TF is published by urdf.launch, /robot_description is set.

Summed up, combination of this PR and the proposed changes would just invert the meaning of pass_tf_args_as_params, as now (in the version released into Noetic), passing pass_tf_args_as_params:=true actually publishes the calibrated transforms, which is non-intuitive based on the name of the argument.

I think the problem in #472 was that urdf.launch overwrites the global /robot_description parameter. It would be better if it would set the driver-private parameter instead, the same way the driver binary does: <camera_name>/robot_description. This might require fixing a few distributed rviz files if there are some, but would result in a consistent experience.

Also, the robot_state_publisher would need a remap from robot_description to ~robot_description.

Serafadam commented 5 months ago

Hi @peci1 @hollydinkel Proposed changes are available in this branch, it would be a great help if you could test and verify them, they should be merged and released this week if there are no issues.

peci1 commented 5 months ago

Thanks @Serafadam , the commit fixes the issue. However, I'd still prefer to invert the logic of pass_tf_args_as_params. I still think the currently implemented behavior does exactly the opposite than one would say based on the name of the argument.

Serafadam commented 5 months ago

@peci1 How about changing it to publish_tf_from_calibration as an argument, is that more explicit?

peci1 commented 5 months ago

Yeah, that sound better ;)