Opposite X and Y between TF and get_current_pose()

Hi,

Here’s a complement for my previous topic

First :

roslaunch ur_robot_driver ur3_bringup.launch robot_ip:=10.31.56.102

When I use MoveIt! :
roslaunch ur3_moveit_config ur3_moveit_planning_execution.launch

rostopic echo -n 1 /tf
transforms: 
  - 
    header: 
      seq: 0
      stamp: 
        secs: 1632812531
        nsecs: 683076397
      frame_id: "base"
    child_frame_id: "tool0_controller"
    transform: 
      translation: 
        x: 0.40397276508452934
        y: -0.05284395305852813
        z: 0.2684066473605699
      rotation: 
        x: -0.8404507390466658
        y: 0.5410578077432447
        z: 0.029860070618397676
        w: 0.0027166336984866496
---

Here, X is positive and Y is negative. It corresponds to the real robot and to the TCP coordinates displayed by the teach pendant (X = 403.98 mm and Y = -52.83 mm). So, OK.

Now, if I use this code :


import sys
import rospy
import moveit_commander

moveit_commander.roscpp_initialize(sys.argv)
rospy.init_node('move_group_python_interface_tutorial',anonymous=True)
robot = moveit_commander.RobotCommander()
group = moveit_commander.MoveGroupCommander("manipulator")

print(group.get_current_pose())

I get this :

header: 
  seq: 0
  stamp: 
    secs: 1632813992
    nsecs: 777175188
  frame_id: "base_link"
pose: 
  position: 
    x: -0.4033402964629966
    y: 0.05497579606279141
    z: 0.26930932855449635
  orientation: 
    x: 0.5431377755932296
    y: 0.8391674130280562
    z: -0.0012092217977459708
    w: 0.028247963078459875


Now, X is negative and Y is positive, but Z is the same than previously. Not OK!
We can notice too that orientations are not the same but the robot was in the same position/orientation (I don’t move it between the two experiments)

Why and how can I correct this to have good values with get_current_pose()?

Thanks,

Philippe

Have a look at the tf tree:

As by rep-proposal-0199, the frame base corresponds to the robot’s base frame. The transformation from base to tool0_controller is published by the robot controller directly.

On the other side we have the “ROS” chain which is also used by MoveIt! It uses the full URDF model and the joint values read from the robot. As base and base_link are effectively rotated by 180 deg, they don’t give the same values.

If you look at they correspond all to the same location (given that your calibration is there):

Furthermore, the transformation between tool0 (the frame coming from the kinematic ROS chain) and tool0_controller (coming from the robot controller directly) should be almost 0.