Release of Dual Quaternions

You’re probably using one or more of these to represent transformations:

  • 4 by 4 homogeneous transformation matrices
  • a quaternion + a vector
  • Euler angles + a vector (yikes)

That’s great! But what if I told you there’s something better, a way to represent elements of SE(3) that

  • is twice as compact as matrices
  • is the natural extension for quaternions to include translations
  • has all these amazing mathematical properties making them superior in many ways to matrices or quaternions + vectors (axis-angle for quaternions becomes screw for dual quaternions, easy ScLERP, easy normalization (vs. Gram-Shmidt), an exact tangent (higher order Taylor series elements are exactly zero), and more
  • is fast (proof: all the graphics people use it)
  • makes your colleagues go “woah! DUAL quaternions?!”

Ever wonder what the shortest path looks like between two frames with constant speed, independent of the coordinate system?

Dual quaternions are the generalization of quaternions to dual numbers. Think of dual numbers as complex numbers except i or j becomes e and e^2 = 0. The math works out really nicely.

It’s super easy to start using dual quaternions right now in ROS, with the recent release of the purely Pythonic dual_quaternions package and dual_quaternions_ros package for converting from and to ROS messages. If there is interest, I’ll add C++ and ROS2 support as well.

apt install ros-$ROSDISTRO-dual-quaternions-ros

pro tip: I also use this to convert Pose messages to Transform messages (don’t ask me why they aren’t the same thing anyways)

Let me know how YOU plan to make dual quaternions a large part of your life. :sweat_smile:

Cheers,
Achile

33 Likes

I’ve got some high-level questions about how dual quaternions work…

I guess one of the quaternions handles orientation, like we’re used to, and it should be a unit quaternion, right? (magnitude of 1)

Does the second quaternion represent translation? And I suppose it doesn’t have a unit magnitude?

Assuming I’m correct that one quaternion handles translation, one handles orientation… Does an axis-angle interpretation make sense for the translation quaternion? Or is there a better way to think about it?

1 Like

This is an important concept for advanced robotics. I’d love to see a C++ version of this!

5 Likes

Excited to see this officially released @Achllle!

3 Likes

This is a great release, particularly in python, as python’s 3D geometry libraries aren’t as fully fleshed out as say C++. I think a ROS 2 port would be a good plan, I usually suggest people, work their way through Melodic, and Noetic to get to ROS 2, as it let’s you compartmentalize tasks (like Python 2=>3 conversion).

Also whenever I hear dual quaternions all I can think of is dueling quaternions.

1 Like

This is a good intro to dual-quaternions: https://cs.gmu.edu/~jmlien/teaching/cs451/uploads/Main/dual-quaternion.pdf

I’ll try to answer briefly. While quaternions are based around the idea that there are three square roots of -1, called i, j, and k, dual numbers are based on the idea that there’s a (non-zero) square root of zero, called \epsilon. This is similar to the \epsilon that shows up in calculus as a very small number that goes away if you square it, but I guess it’s formally different in ways I’ve never really dug into. So a dual number has the form r + d \epsilon, with the obvious addition rule and the multiplication rule (r1 + d1 \epsilon) x (r2 + d2 \epsilon) = r1 x d1 + (r1 x d2 + r2 x d1) \epsilon.

Now, for dual quaternions, just let the r and d variables represent quaternions instead of scalars, and do the arithmetic contortions of using both dual number multiplication and quaternion multiplication. What you get is a handy way to represent SE3 transforms, although the connection to a translation and rotation is even less intuitive than the connection from a quaternion to a 3-D rotation. The real-part quaternion represents the rotation exactly the same as the SO3 quaternions you’re familiar with. If you look at the dual number multiplication, the real part of the product has no dependence on the dual parts of the multiplicands, which makes sense because the rotation that results from composing SE3 transforms is unaffected by the translations. The dual-part quaternion, though, is an ugly mix of rotation and translation. I’m not even going to write it out–it’s in the paper I linked above. While it’s possible to squint at a quaternion and make out an axis and an angle, I don’t think there’s any way to make that much sense of the dual-part quaternion. (I’d be happy if someone could tell me otherwise, though!)

Finally, an SE3 transform is represented as a unit dual-quaternion, so dq x dq* = 1 + 0 \epsilon, where * is the quaternion conjugate, not the dual conjugate. If you work through the arithmetic, this means that the real-part quaternion is a unit quaternion, and the remaining condition is that r* x d + r x d* = 0.

4 Likes

Great tool, thanks for your work on this! I am interested in C++ and ROS2 support, and I’m also willing to help out.

Yes, please make a C++ / ROS2 version. Please add a couple of beginner tutorials for the ROS2 version as well… Use: autonomous vehicles with lots of perception sensors mounted all over… grin!

Awesome! Great to see this release :smiley:

1 Like

I did a little digging to see if anyone tried to add this to Eigen. I found a PR which may be possible alternative for C++.

Found another C++ implementation which may be a better solution for c++ using Eigen.

3 Likes

Cool stuff, and cool visualization. How about releasing that as an example?

While quaternions are based around the idea that there are three square roots of -1, called i, j, and k, dual numbers are based on the idea that there’s a (non-zero) square root of zero, called \epsilon.

Thanks for the clarification and the paper link. On first read I didn’t even catch that this refers to dual numbers instead of just using a second quaternion to represent translation (somehow).

  • [dual quaternion representation] is fast (proof: all the graphics people use it)

It seems that the main strength of this representation is ScLERP interpolation. For computer graphics and animation, the value of interpolating efficiently between keyframes is immediately clear, but the importance in robotics (e.g. for motion planning) is not as evident to me.

Is there an estimate on which operations would be faster with dual quaternions than the current ROS standard vector+quaternion? E.g. for forward kinematics calculations or collision detection? Sadly, the paper @JStech linked only compared the calculation cost of dual quaternions vs Matrix multiplications, and omitted the vector+quaternion representation (why?).

Another concern is that accessing the translation of a pose or transform appears to require a scalar-quaternion and a quaternion-quaternion multiplication. I don’t know how pyquaternion optimises multiplications, but if I am reading it right that should be 16 multiplications and 9 additions. It seems like this would make distance checks (and pure translations in general) a lot more cumbersome.

Not to detract from this approach, it is very cool and other factors like numerical stability or the interpolation properties may make it worth using immediately in certain algorithms. But I would like to have a better idea of the effects on performance before converting existing projects.

axis-angle for quaternions becomes screw for dual quaternions

If anyone else didn’t know about this axis-angle property of quaternions for some reason, I recommend this interactive video.

PS: I assume that for everything that users touch or where someone has to enter coordinates, human-readable translation vectors are indispensable, since the biggest cost for robotics systems is still setup and maintenance. For what it’s worth, we usually use tf quaternions to set RPY values in our code for simplicity.

1 Like

This is really interesting, I’ve been reading about dual quaternions and I’m so glad to see a ROS package! Thank you @Achllle

Also, +1 for the C++ support.

1 Like

haha @Katherine_Scott- your link made my morning :slight_smile:

Hi @Achllle

Thank you for the cool package. I wanted to play around with the sclerp method with some interactive markers like you did in your gif but I’m seeing some weird behavior. Not to make this into a debugging thread - I’ll create an issue for it on the github page of course - but I just wanted to mention it while saying thanks :slightly_smiling_face:

Ignoring some import problems I had with dual_quaternions_ros (which is why the from_ros and to_ros are duplicated in my class) I did a simple sclerp test like below (based on your gist https://gist.github.com/Achllle/c06c7a9b6706d4942fdc2e198119f0a2) .

    def _create_sclerp_interpolated_path(self, start_pose, end_pose, samples):
        dq_start = self.from_ros(start_pose)
        dq_stop = self.from_ros(end_pose)
 
        interpolated_poses_path = Path()
        interpolated_poses_path.poses.clear()
        interpolated_poses_path.header.frame_id = "map"
        interpolated_poses_path.header.stamp = rospy.Time.now()
       
        taus = np.linspace(0.0, 1.0, num=samples)
        for tau in taus:
            intermediate_dq = dq_stop.sclerp(dq_start, dq_stop, tau)
            p = PoseStamped()
            p.header.frame_id = self.marker_frame
            p.header.stamp = rospy.Time.now()
            p.pose = self.to_ros_pose(intermediate_dq)
            interpolated_poses_path.poses.append(p)

        return interpolated_poses_path

However, depending on how I rotate the start and end dual quaternions the starting dual quaternion used to calculate the intermediate ones jumps around. More precisely, it looks like all x, y and z coordinates for the starting dual quaternion are multiplied by -1 sometimes.
See this video which makes it more clear: Interactive marker dq sclerp

I haven’t narrowed the problem down further yet (partly because I don’t really understand the DQ maths :confused: ), but was wondering if you can replicate the problem. In your gist you always start your sclerp / screw tests from an identity quaternion and of course the problem won’t show up in that specific case.

Thanks again!

Edit:

I had a quick look at the sclerp implementation in dual_quaternions:

    @classmethod
    def sclerp(cls, start, stop, t):
        """Screw Linear Interpolation
        Generalization of Quaternion slerp (Shoemake et al.) for rigid body motions
        ScLERP guarantees both shortest path (on the manifold) and constant speed
        interpolation and is independent of the choice of coordinate system.
        ScLERP(dq1, dq2, t) = dq1 * dq12^t where dq12 = dq1^-1 * dq2
        :param start: DualQuaternion instance
        :param stop: DualQuaternion instance
        :param t: fraction betweem [0, 1] representing how far along and around the
                  screw axis to interpolate
        """
        # ensure we always find closest solution. See Kavan and Zara 2005
        if (start.q_r * stop.q_r).w < 0:
            start.q_r *= -1
        return start * (start.inverse() * stop).pow(t)

Commenting out the Kavan and Zara 2005 addition, I no longer see the weird translational inversion behavior, however the interpolated path can now become really strange and looooong. See this video as a short test: Modified sclerp

This is a good intro to dual-quaternions

That’s right, it’s in the references of the repo :smile:

This is similar to the \epsilon that shows up in calculus as a very small number that goes away if you square it, but I guess it’s formally different in ways I’ve never really dug into.

They’re very different. Other than the unfortunate use of the same Greek letter, the two have very different meanings! Epsilon in a dual number is a purely mathematical construct that has nothing to do with ‘a very small value’.

I don’t think there’s any way to make that much sense of the dual-part quaternion. (I’d be happy if someone could tell me otherwise, though!)

It’s actually very analogous to how a quaternion relates to axis-angle, but with screw parameters. And the dual part of can very easily be calculated as follows:
image
For the details, I’d refer to Dual Quaternions by Yan-Bin Jia. That interpolation you see in the gif, is ScLERP (Screw Linear Interpolation). Turns out the shortest path is the same as converting the dual quaternion to a screw and taking linear steps while you revolve around the screw axis! But I definitely can’t squint at a dual quaternion and make much sense of it, although tbh I can’t do that either for a regular quaternion :slight_smile:

Thanks for the note on the unit dual quaternion, very important indeed!

1 Like

Thanks @felixvd!

Clicking on the gif in the repo takes you to the gist :wink:

Great questions you ask about speed and use! An example of where dual quaternions speeds up calculations would be in hand-eye calibration problems, or any (perception) problem that boils down to solving a system in the form of AX=XB. I strongly recommend Daniliidis’ work on hand-eye calibration as it cleared up quite a few things for me. The speed comes from faster convergence, although I think dual quaternion operations require fewer operations than matrix multiplication (proof left as exercise to the reader?). That paper also describes the downsides of quaternion + vector which is basically that you’re treating rotation and translation separately, which is not a ‘natural’ way to represent SE(3) elements (geometers: a geodesic?) Modern motion planners make use of optimization, and if you’re minimizing an objective in the form of a transformation, so I think it would make sense to at least explore the option. I’ve written motion planners myself, and I think it’s hard to argue against using Python for prototyping.

I don’t know how pyquaternion optimises multiplications

Unfortunately, I had to resort to pyquaternion for the release, but I actually was using the much more efficient numpy-quaternion before (which you can still go use). The reason I had to switch is because numpy-quaternion has dependencies that were unreleasable in Kinetic (and I didn’t have the bandwidth to do both). It should be straightforward to switch back though.

Thanks for giving it a go and writing that up! Challenges my own understanding every time :slight_smile:

If by jumping around you mean the switching between the upward arc and downward arc in your first video, that happens when the axis required to get rotate from one to the other (perpendicular to your screen) is close to the translation axis between the two poses, and as soon as it crosses that virtual line, all the intermediate poses flip. The other behavior with the starting poses not aligning or the larger circle forming seems odd and I have not seen that myself. I definitely just wrote the visualization code to support above gif… If you could open an issue on the dual quaternions repo, I’ll look into it more.

Transformation of a 3D vector requires significantly less operations using a matrix than a dual quaternion (Transformation is 16 multiplications and 12 additions if you’re not using the fact that our transformation matrices are isometric which is already less than the 15 multiplications and 15 additions of a single quaternion rotation).

Multiplication of two dual-quaternions are three quaternion multiplications and one quaternion addition (16 multiplications and 12 additions for each quaternion multiplication and 4 additions for the quaternion addition) which makes 48 multiplications and 40 additions in total.
A matrix multiplication on the other hand requires 64 multiplications and 48 additions (or 48 multiplications and 36 additions if you use the fact that the transformations we are talking about are isometric).

In summary, assuming that the numbers above are correct, if you’re multiplying transformations, dual quaternions will be around the same speed, if you want to transform a lot of 3D points, using matrices will be significantly faster. Unless your matrix doesn’t stay in cache which is unlikely.

PS: You only leave the proof to the reader if you already know there is proof that your statement is true. It’s not a “I think it’s true but too lazy to check” excuse :stuck_out_tongue:

Some of my colleagues use this C++ library, it’s easy to install and has versions for Matlab and Python as well.