UniversalRobots / Universal_Robots_ROS_Driver

Universal Robots ROS driver supporting CB3 and e-Series
Apache License 2.0
767 stars 405 forks source link

Why /Joint_states topic publishes the joint states in the wrong order? #619

Closed SCerq closed 1 year ago

SCerq commented 1 year ago

Summary

Hi There!

When I do rostopic echo /joint_states I receive the joint state information with the following joint order:

name: 
  - elbow_joint
  - shoulder_lift_joint
  - shoulder_pan_joint
  - wrist_1_joint
  - wrist_2_joint
  - wrist_3_joint

However, the _ur10econtrollers.yaml config file from the ROS driver is in the correct order.

Settings for ros_control hardware interface
ur_hardware_interface:
   joints: &robot_joints
     - shoulder_pan_joint
     - shoulder_lift_joint
     - elbow_joint
     - wrist_1_joint
     - wrist_2_joint
     - wrist_3_joint

Also, I recently attempt to send velocity commands to the _/joint_group_velcontroller/command topic. I sent the joint velocities in the correct order (shoulder_pan_joint, shoulder_lift_joint, elbow_joint, ...) and I observed that the movement was correct, the base and the elbow moved in the way it was supposed. However the joint_states topic presented its values in the wrong order (elbow_joint, shoulder_lift_joint, shoulder_pan_joint, ...)

Can someone explain me why this happens?

I also searched in the code for a configuration file that might be wrongly written. However the only file I found was the UR10e.srdf file, inside the folder config, inside the ur10e_moveit_config. I already swtich the order of this, but it made no difference image

Thank you very much!

Versions

RobertWilbrandt commented 1 year ago

This is expected behavior - In general you should not rely on the order of joints on the /joint_states topic. In more complex hardware setups it is even common for all components to publish their state to the same topic, so always looking at the name field and only using the values you are looking for is recommended.

The reason for this order lies within the ros_control framework this driver uses: It exposes a set of interfaces based on the ur10e_controllers.yaml file you showed, which are then used by different controllers to read data from the arm or control it. The /joint_state values are published by a joint_state_controller/JointStateController, which by default publishes the states from all interfaces it sees on the hardware. The order in this transfer from hardware interface to controller is however not preserved, for the technical information on that see this issue.

The reason for the different order in the joint_group_vel_controller case can be seen here: It explicitly uses the joints in the order you defined in the file. This is generally done by all controllers that actually want to move joints.

The SRDF file is not related to this, it is only used inside of moveit.

If you want to deal with this in your code my recommendation is: In your subscriber, traverse the name field. If your current joint name matches one of the joints you are interested in, use the position/velocity/... values at this index. If you don't care about a joint, just ignore it.

SCerq commented 1 year ago

Dear @RobertWilbrandt, thank you very much for the explanation! it was very enlightening! Now I can understand better the cause.

Kind Regards

RobertWilbrandt commented 1 year ago

Without fürther questions i'll go ahead and close this then

gavanderhoorn commented 1 year ago

Just to keep things connected: this question has come up many times in the past. https://github.com/ros-industrial/ur_modern_driver/issues/113 already linked is only one instance.

Some Q&As on ROS Answers for instance: