2 # Dealing with Lie group geometry
4 Pinocchio relies heavily on Lie groups and Lie algebras to handle motions and more specifically rotations.
5 For this reason it supports the following special groups \\( SO(2), SO(3), SE(2), SE(3) \\) and implements their associated algebras
6 \f$ \mathfrak{se}(2) , \mathfrak{se}(3) \f$.
7 It has various applications like representing the motion of a robot free flyer joint (typically the base of a mobile robot),
8 or the motion of the robot links. The later is particularly useful for collision detection.
9 It is also interesting to have general vector space over which a Lie algebra is defined.
12 ## Using \\( SE(2) \\) with pinocchio in C++
14 As a motivating example let us consider a mobile robot evolving in a plane \f$(\mathbb{R}^2 \times \mathbb{S}^1 \f$).
15 
17 The robot starts at position \f$ pose_s = (x_s,y_s,\theta_s) \f$ and after a rigid motion
18 \f$ \delta_u=(\delta x,\delta y,\delta \theta) \f$
20 at \f$ pose_g = (x_{g},y_{g},\theta_{g})\f$.
21 It is possible to instantiate the corresponding \\(SE(2)\\) objects using:
24 typedef double Scalar;
27 SpecialEuclideanOperationTpl<2,Scalar,Options> aSE2;
28 SpecialEuclideanOperationTpl<2,Scalar,Options>::ConfigVector_t pose_s,pose_g;
29 SpecialEuclideanOperationTpl<2,Scalar,Options>::TangentVector_t delta_u;
31 You can change Scalar by another type such as float.
34 In this example, \f$ pose_s=(1,1,\pi/4)\f$ and \f$ pose_g=(3,1,-\pi/2) \f$ and we want to compute
37 pose_s(0) = 1.0; pose_s(1) = 1.0;
38 pose_s(2) = cos(M_PI/4.0); pose_s(3) = sin(M_PI/4.0);
39 pose_g(0) = 3.0; pose_g(1) = -1.0;
40 pose_g(2) = cos(-M_PI/2.0); pose_g(3) = sin(-M_PI/2.0);
42 aSE2.difference(pose_s,pose_g,delta_u);
43 std::cout << delta_u << std::endl;
46 aSE2 is used to compute the difference between two configuration vectors representing the two poses. Note that the rotation is represented by two numbers \f$ sin(\theta),cos(\theta)\f$ which is also a \f$ SO(2) \f$ object.
47 The difference lies in the tangent space of \f$ SE(2)\f$ and is representend by a vector of 3 reals.
48 Therefore the output is:
56 Note that the linear part is not following a straight path, it also takes into account
57 that the system is rotating.
59 We can verify that this is the appropriate motion by integrating:
61 SpecialEuclideanOperationTpl<2,Scalar,Options>::ConfigVector_t pose_check;
63 aSE2.integrate(pose_s,delta_u,pose_check);
64 std::cout << pose_check << std::endl;
76 ## Using \f$ SE(3) \f$ with pinocchio in C++
78 Our mobile robot is not in a plane but in a 3-dimensional space. So let's consider a object in our physical space. This is actually almost the same case, we want the object from one position to an other position. The difficulty lies in the fact that we now have three dimensions so the object has six degrees of freedom, three corresponding to its translation and three to its rotation.
80 
82 It is also possible to instantiate the corresponding object which is now a \f$ SE(3) \f$ object using the same algorithm and changing the dimension parameter:
85 typedef double Scalar;
88 SpecialEuclideanOperationTpl<3,Scalar,Options> aSE3 ;
89 SpecialEuclideanOperationTpl<3,Scalar,Options>::ConfigVector_t pose_s,pose_g;
90 SpecialEuclideanOperationTpl<3,Scalar,Options>::TangentVector_t delta_u ;
93 In this example, \f$ pose_s=(1,1,1,\pi/2,\pi/4,\pi/8)\f$ and \f$ pose_g=(4,3,3,\pi/4,\pi/3, -\pi) \f$. For the starting position, there is first a rotation around the y-axis then the x-axis and finally the z-axis. For the final position, the rotations are in this order, x-axis, y-axis, z-axis. We want to compute \f$ \delta_u \f$.
95 - For the first pose, we have the three rotations matrices for each rotation :
98 \begin{bmatrix} 1 &0 &0 \\ 0 &cos(\pi/8) &-sin(\pi/8) \\0 &sin(\pi/8) &cos(\pi/8) \end{bmatrix} \ \ R_{y_s} = \begin{bmatrix} cos(\pi/4) &0 &sin(\pi/4) \\ 0 &1 &0 \\-sin(\pi/4) &0 &cos(\pi/4) \end{bmatrix} \ \ R_{z_s} = \begin{bmatrix} cos(\pi/2) &-sin(\pi/2) &0 \\sin(\pi/2) &cos(\pi/2) &0 \\ 0 &0 &1\end{bmatrix} \f$
100 Therefore, the complete rotation is:
102 \f$ R_{pose_s} = R_{s_z} * R_{s_x} * R_{s_y} = \begin{bmatrix} 0 &-1 &0 \\ cos(\pi/4)*cos(\pi/8) + sin(\pi/4) * sin(\pi/8) &0 &sin(\pi/4) * cos(\pi/8) - cos(\pi/4) * sin(\pi/8) \\ sin(\pi/8) * cos(\pi/4) - cos(\pi/8) * sin(\pi/4) &0 &sin(\pi/4) * sin(\pi/8) + cos(\pi/4) * cos(\pi/8) \end{bmatrix} \f$
104 - For the second one, we have:
107 \begin{bmatrix} 1 &0 &0 \\ 0 &cos(\pi/4) &-sin(\pi/4) \\0 &sin(\pi/4) &cos(\pi/4) \end{bmatrix} \ \ R_{y_g} = \begin{bmatrix} cos(\pi/3) &0 &sin(\pi/3) \\ 0 &1 &0 \\ -sin(\pi/3) &0 &cos(\pi/3) \end{bmatrix} \ \ R_{z_g} = \begin{bmatrix} cos(-\pi) &-sin(-\pi) &0 \\ sin(-\pi) &cos(-\pi) &0 \\ 0 &0 &1\end{bmatrix} \f$
109 The complete rotation is:
112 \begin{bmatrix} -cos(\pi/3) &-sin(\pi/3) * sin(\pi/4) &-cos(\pi/4) * sin(\pi/3) \\ 0 &-cos(\pi/4) &sin(\pi/4) \\ -sin(\pi/3) &sin(\pi/4) * cos(\pi/3) &cos(\pi/3) * cos(\pi/4) \end{bmatrix} \f$
115 To compute \f$ \delta_u \f$ using Pinocchio we need to transform \f$ R_{pose_s} \f$ and \f$ R_{pose_g} \f$ matrices into quaternions using:
118 float s = 0.5f / sqrtf(trace+ 1.0f);
119 q.x = ( R[2][1] - R[1][2] ) * s;
120 q.y = ( R[0][2] - R[2][0] ) * s;
121 q.z = ( R[1][0] - R[0][1] ) * s;
125 The quaternions components are:
126 - For the first rotation
142 For each pose we have now a mathematical object with seven components and both are normalized. As for the \f$ SE(2) \f$ example we compute \f$ \delta_u \f$ using:
145 pose_s(0) = 1.0; pose_s(1) = 1.0;
146 pose_s(2) = 1 ; pose_s(3) = -0.13795 ;
147 pose_s(4) = 0.13795; pose_s(5) = 0.69352; pose_s(6) = 0.69352;
148 pose_g(0) = 4; pose_g(1) = 3 ;
149 pose_g(2) = 3 ; pose_g(3) = -0.46194;
150 pose_g(4) = 0.331414; pose_g(5) = 0.800103; pose_g(6) = 0.191342;
152 aSE3.difference(pose_s,pose_g,delta_u);
153 std::cout << delta_u << std::endl;
156 The difference lies in the tangent space of \f$ SE(3)\f$ and is represented by a vector of 6 reals which is:
167 The three first values are linear and the three last are velocities.
169 To verify it is the good solution, we integrate:
172 SpecialEuclideanOperationTpl<3,Scalar,Options>::ConfigVector_t pose_check;
174 aSE3.integrate(pose_s,delta_u,pose_check);
175 std::cout << pose_check << std::endl;
192 ## Using interpolation to plot a trajectory with pinocchio in C++
194 Assuming that we want to make the robot pass through known positions, we can use interpolations to plot a trajectory.
196 The problem is an interpolation such as Lagrange's one only takes into account translations whlie the robot interact with its environment by performing translations and rotations.
198 A possibility is to use the \f$ \delta_{theta} \f$ method by using quaternions. The method is simple, we just vary the angle, the scalar component of the quaternion, with very small variations.
200 Let's consider the previous example, we can interpolate trajectory using:
202 SpecialEuclideanOperationTpl<3,Scalar,Options>::ConfigVector_t pole;
203 aSE3.interpolate(pose_s,pose_g,0.5f, pole);
204 std::cout << pole << std::endl;
207 The output corresponds to the middle of the trajectory and is: