URDF with tool-changer
Consider the application of a robot w/ tool changer that needs to update its URDF.
I'd like to dynamically change the origin of a joint that connects an END_EFFECTOR link to a TOOL link.
The approaches I can think of are:
Model the joint as a FIXED joint
My first approach was to model the joint as a fixed joint, and publish its transform to /tf myself. However robot_state_publisher continued to publish the transform described in the URDF, conflicting with the values I was publishing. I could patch robot_state_publisher, but I'd like to avoid modifying a standard library if possible.
Then I tried taking the approach of parsing the robot_description rosparam, modifying its XML, and writing it back to the rosparam whenever the tool changed. I believe this is how the calibration stack handles adjusting fixed joints. But I don't think a change to the robot_description rosparam is propagated to robot_state_publisher at run-time unless I modify it to use dynamic_reconfigure, for example.
Model the joint as a FLOATING joint
I thought this could work and I could publish the transform to /tf directly without conflicting with robot_state_publisher. But in my Electric install the kdl_parser does not support 'FLOATING' type joints. It throws the warning "Converting unknown joint type into a fixed joint". After reading https://code.ros.org/trac/ros-pkg/ticket/4000 (this ticket) I'm very confused as to whether floating joints are supported at all.
Model the joint as the sum of six REVOLUTE joints
This is the approach suggested by Wim https://code.ros.org/gf/project/ros/mailman/?_forum_action=ForumMessageBrowse&thread_id=23468&action=ListThreads&mailman_id=20 (here). Then robot_state_publisher could be responsible for publishing to /tf, but it seems ugly.