0

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:

  • Running ROS Melodic on Ubuntu 18.04
  • Simulating UR5 robot arm in RViz and Gazebo but also have the physical arm

Questions

  • 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?
  • Can I convert from (x, y, z, roll, pitch, yaw) to quaternion? Or do those describe two different things?
  • Do quaternions have to be normalized so that the sum of squares equals one? If so, how can I tell my robot arm to go to a physical point in space like (0.5m, 0.3m, 0m)?
  • Can someone provide a layman's terms explanation of describing rotation (3D) with a quaternion (4D)?
lg22woo
  • 106
  • 3
  • 10

1 Answers1

1

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!

Rafael
  • 7,002
  • 5
  • 43
  • 52
  • Great, thanks! This helps break down my problem into two sections: how to send position and how to send rotation/orientation. I feel comfortable with quaternions or at least converting from euler angles now, but I'm still not sure how to send the robot a position command. How can I tell the robot how to move to a fully defined position and orientation in space? – lg22woo Mar 24 '20 at 22:47
  • You define this information in your `pose_goal.position` object. You also need to specify the orientation as a quaternion instead of Euler angles. Once you set these properties of your `pose_goal` and send it as a goal to MoveIt! then MoveIt! will do the rest (find an Inverse Kinematics solution to your pose and then plan a trajectory to move UR5 there). – Rafael Mar 24 '20 at 22:51
  • Also, when you say "break it down to two problems", you don't need to do this. A pose (i.e., your `pose_goal`) defines both the position and orientation of where the Robot's end-effector should be in space (it tells both the position and the orientation). That's it. You just send this pose (which again is position AND orientation combined) to a planner and it will find a solution and exeucte it. – Rafael Mar 24 '20 at 23:05
  • Now that you point it out, it's pretty straightforward how it works. `pose_goal.position` has components `x, y, z` and `pose_goal.orientation` has (quaternion) components `x, y, z, w`. Thank you for your help! – lg22woo Mar 24 '20 at 23:06
  • I have updated my answer with more detailed code, in case you haven't yet solved your problem. – Rafael Mar 25 '20 at 00:41
  • Thanks @Rafael , that's very helpful. I was able to convert my desired roll, pitch, yaw to quaternion then pass that to `pose_goal.orientation` to do what I wanted. Thanks again! – lg22woo Mar 26 '20 at 19:31