pythonrosquaternionsmoveit

Practical Understanding of Quaternions in ROS / MoveIt


tl;dr: How can I send a 6 DOF robot arm a "move to (x, y, z, roll, pitch, yaw)" command using ROS MoveIt?

I'm trying to control a Universal Robots UR5 6-degree-of-freedom robot arm with ROS and MoveIt, using the Python Move Group Interface. I'm missing the fundamental "how to send robot end effector to this point" control. I'm interpreting "end effector" as the "hand" of the robot on the very end. Intuitively, I want to make the end effector move using something like:

pose_goal.position.x = x_coordinate # x, y, z, r, p, y are in a fixed reference frame
pose_goal.position.y = y_coordinate
pose_goal.position.z = z_coordinate
pose_goal.orientation.roll = roll_angle
pose_goal.orientation.pitch = pitch_angle
pose_goal.orientation.yaw = yaw_angle

move_group.set_pose_target(pose_goal)
plan = move_group.go(wait=True)

But, the geometry_msgs.msg.Pose() object wants a quaternion in the format (x, y, z, w).

Some things I have done / researched:

Some other info:

Questions


Solution

  • My research says that a quaternion of form (x, y, z, w) describes rotation in 3D space only. How does the robot know what position to move to if it only gets rotation information?

    Correct, a quaternion describes the orientation of a frame only; you also need to specify the position of the frame to have a complete pose. Quaternion is just a different way to describe the orientation of a body, another way is, as you already mentioned, to use Euler Angles (Yaw, Pitch, Roll).

    In your case with your pose_goal object, you need to specify the position of the desired/goal robot pose by setting the x, y and z components of pose_goal.position (that's the position of the Robot in 3D space) and then also specify the orientation of the desired/goal robot pose by using the Quaternion notation w, x, y and z to set the components of pose_goal.orientation (note that x, y and z part of the Quaternion is not the same with your position vector, they are different things). Once you define both pose_goal.position and pose_goal.orientation you are done, you have a complete pose that you can send to MoveIt! to plan and execute.

    Can I convert from (x, y, z, roll, pitch, yaw) to a quaternion? Or do those describe two different things?

    Here, x, y, z, is your position vector which has nothing to do with the orientation (and hence with quaternions), so your question should really be, "Can I convert Euler angles (roll, pitch, yaw) to a quaternion?" and the answer is, yes you can convert Euler angles to a quaternion but it might be tricky. If you can represent the orientation using a quaternion (i.e., if you have this information already) you should use it as quaternions are more numerically robust and they are not suffering from singularities (for example Euler angles could cause a Gimbal lock where under a specific configuration your system loses a degree of freedom).

    If you have access to a quaternion, use it and forget Euler angles, else you might want to try converting the Euler angles to a quaternion using the following way using ROS's tf library:

    from tf.transformations import quaternion_from_euler
    
    # Pose Position
    pose_goal.position.x = x_coordinate
    pose_goal.position.y = y_coordinate
    pose_goal.position.z = z_coordinate
    
    # Pose Orientation
    quaternion = quaternion_from_euler(roll_angle, pitch_angle, yaw_angle)
    
    pose.orientation.x = quaternion[0]
    pose.orientation.y = quaternion[1]
    pose.orientation.z = quaternion[2]
    pose.orientation.w = quaternion[3]
    
    move_group.set_pose_target(pose_goal)
    plan = move_group.go(wait=True)
    

    See tf.transformations.quaternion_from_euler(ai, aj, ak, axes='sxyz') where ai, aj, ak are roll, pitch and yaw respectively and the axes parameter defines the order in which the angles are applied (which is very important)

    (Haven't tested it myself, but might worth the effort)

    Can someone provide a layman's terms explanation of describing rotation (3D) with a quaternion (4D)?

    Quaternions are a bit complex, but there is a great video here explaining them in an interactive way. In general, and in my experience, Quaternions can be a bit frustrating at the beginning and you might find it hard to grasp the concept initially, so keep this in mind while studying them and be patient!