Position and Pose

Joint Position Description

The LeBai LM3 robot is a six-axis (six-joint) robot. The rotation amount of each joint forms the joint position description (referred to as joint position), which can be represented as a six-tuple:

(j1,j2,j3,j4,j5,j6) (j_1, j_2, j_3, j_4, j_5, j_6)

Where jij_i represents the rotation angle of the i-th joint, in radians (rad).

In Lua code, it is represented by an associative array with specified index keys. For example, for the joint position

(j1=0.024rad,j2=15,j3=π,j4=π2,j5=30,j6=0) (j_1=0.024\,\mathrm{rad}, j_2=-15^\circ, j_3=\pi, j_4=\frac{\pi}2, j_5=30^\circ, j_6=0)

can be represented as:

{j1=0.024, j2=math.rad(-15), j3=math.pi, j4=math.pi/2, j5=math.rad(30), j6=0}

The range of joint description is theoretically unlimited, with specific limitations depending on the particular application scenario and potential self-interference.

Cartesian Space Pose Description

The Cartesian position and orientation of the LeBai robot end-effector (referred to as spatial position or pose) is represented as a six-tuple:

(x,y,z,α,β,γ) (x, y, z, \alpha, \beta, \gamma)

Where (x,y,z)(x, y, z) represents the spatial Cartesian coordinate position in meters (m). (α,β,γ)(\alpha, \beta, \gamma) represents the rotational pose in radians (rad).

In Lua code, it is represented by an array with numeric sequential indices:

{x, y, z, alpha, beta, gamma}

For describing coordinate system (pose) {B}\{B\}, we use the following descriptions:

  • X-Y-Z fixed angle. First, align coordinate system {B}\{B\} with the known reference coordinate system {A}\{A\}. Then rotate {B}\{B\} around X^A\hat{X}_A by angle γ\gamma, then around Y^A\hat{Y}_A by angle β\beta, and finally around Z^A\hat{Z}_A by angle α\alpha.
  • Z-Y-X Euler angles. First, align coordinate system {B}\{B\} with the known reference coordinate system {A}\{A\}. Then rotate {B}\{B\} around Z^B\hat{Z}_B by angle α\alpha, then around Y^B\hat{Y}_B by angle β\beta, and finally around X^B\hat{X}_B by angle γ\gamma.
  • RPY rotation angles. X-Y-Z fixed angles can also be defined as RPY rotation angles, i.e., Roll angle RR, Pitch angle PP, and Yaw angle YY. First, align coordinate system {B}\{B\} with the known reference coordinate system {A}\{A\}. Then rotate {B}\{B\} around X^A\hat{X}_A by the roll angle, then around Y^A\hat{Y}_A by the pitch angle, and finally around Z^A\hat{Z}_A by the yaw angle.

The rotational pose of LeBai robots is described using Z-Y-X Euler angles. Their relationship is as follows:

EulerZYX(α,β,γ)=XYZ(γ,β,α)=RPY(γ,β,α) {EulerZYX}(\alpha, \beta, \gamma) = {XYZ}(\gamma, \beta, \alpha) = {RPY}(\gamma, \beta, \alpha)

When developers need to convert between LeBai's pose and other pose representations, transformation through selection matrices is required. RPY or quaternions are commonly used to describe orientation in computer programming. Here's the formula for converting RPY to matrix:

RPY(γ,β,α)=(cosαcosβcosαsinβsinγsinαcosγcosαsinβcosγ+sinαsinγsinαcosβsinαsinβsinγ+cosαcosγsinαsinβcosγcosαsinγsinβcosβsinγcosβcosγ) {RPY}(\gamma, \beta, \alpha)=\begin{pmatrix} \cos\alpha \cos\beta & \cos\alpha \sin\beta \sin\gamma - \sin\alpha \cos\gamma & \cos\alpha \sin\beta \cos\gamma + \sin\alpha \sin\gamma \\ \sin\alpha \cos\beta & \sin\alpha \sin\beta \sin\gamma + \cos\alpha \cos\gamma & \sin\alpha \sin\beta \cos\gamma - \cos\alpha \sin\gamma \\ -\sin\beta & \cos\beta \sin\gamma & \cos\beta \cos\gamma \end{pmatrix}

Here's the formula for converting a 3×3 rotation matrix to RPY:

(r0r1r2r3r4r5r6r7r8)=RPY(γ,β,α),{β=arctan2(r6,r02+r32),β[π2,π2]α=arctan2(r3cosβ,r0cosβ),α[π,π]γ=arctan2(r7cosβ,r8cosβ),γ[π,π] \begin{pmatrix} r_0 & r_1 & r_2 \\ r_3 & r_4 & r_5 \\ r_6 & r_7 & r_8 \\ \end{pmatrix}= RPY(\gamma, \beta, \alpha), \begin{cases} \beta&=\arctan2\left(-r_6, \sqrt{r_0^2+r_3^2}\right), &\beta\in\left[-\dfrac{\pi}2, \dfrac{\pi}2\right] \\ \alpha&=\arctan2\left(\dfrac{r_3}{\cos\beta}, \dfrac{r_0}{\cos\beta}\right) , & \alpha\in[-\pi, \pi] \\ \gamma&=\arctan2\left(\dfrac{r_7}{\cos\beta}, \dfrac{r_8}{\cos\beta}\right) , & \gamma\in[-\pi, \pi] \end{cases}

Specifically, when β=π2|\beta|=\dfrac{\pi}{2}, cosβ=0\cos\beta=0. In this case, take γ=0\gamma=0, and α=arctan2(r1,r4)\alpha=\arctan2(-r_1, r_4).

Here's the conversion implementation in KDL (C++):

Rotation Rotation::EulerZYX(double Alfa,double Beta,double Gamma) {
    return RPY(Gamma,Beta,Alfa);
}

void Rotation::GetEulerZYX(double& Alfa,double& Beta,double& Gamma) const {
    GetRPY(Gamma,Beta,Alfa);
}

Rotation Rotation::RPY(double roll,double pitch,double yaw) {
    double ca1,cb1,cc1,sa1,sb1,sc1;
    ca1 = cos(yaw); sa1 = sin(yaw);
    cb1 = cos(pitch);sb1 = sin(pitch);
    cc1 = cos(roll);sc1 = sin(roll);
    return Rotation(ca1*cb1,ca1*sb1*sc1 - sa1*cc1,ca1*sb1*cc1 + sa1*sc1,
                    sa1*cb1,sa1*sb1*sc1 + ca1*cc1,sa1*sb1*cc1 - ca1*sc1,
                    -sb1,cb1*sc1,cb1*cc1);
}

// Gives back a rotation matrix specified with RPY convention
void Rotation::GetRPY(double& roll,double& pitch,double& yaw) const {
    double epsilon=1E-12;
    pitch = atan2(-data[6], sqrt( sqr(data[0]) +sqr(data[3]) )  );
    if ( fabs(pitch) > (PI_2-epsilon) ) {
        yaw = atan2(  -data[1], data[4]);
        roll  = 0.0 ;
    } else {
        roll  = atan2(data[7], data[8]);
        yaw   = atan2(data[3], data[0]);
    }
}

Robot Kinematics

For robot motion, when joint positions are specified, theoretically any position can be reached as long as self-interference (i.e., hitting itself) does not occur. When a set of joint positions is determined, and the TCP settings are determined, the robot's pose is also determined and unique. This calculation process is the robot's forward kinematics.

When specifying spatial positions, the situation becomes quite different. Due to the robot's configuration, the inverse kinematics of converting spatial positions to joint positions has multiple solutions or no solution. The robot cannot reach any arbitrary point in space, which is a physical limitation. The robot also cannot perform arbitrary motion between two points in space—this phenomenon is particularly evident when the robot is in a "singular position", where executing spatial movement commands is likely to cause algorithm failure, forcing the robot to stop moving.

When the following error messages appear during robot motion, please modify the movement commands in the scene or program, and use teaching or joint movement to restore the robot to a normal position.

  • 1140 Robot motion planning error
  • 1010 Robot cannot reach that position

D-H Parameters

LeBai robots use modified D-H parameters for kinematic description of the robot.

Jointθ\thetadid_i (unit: m)ai1a_{i-1} (unit: m)αi1\alpha_{i-1} (unit: rad)
100.2158300
20001.5708
300-0.280
400.12063-0.260
500.0983301.5708
600.083430-1.5708

Due to manufacturing and assembly errors, there will always be some deviation between the actual DH parameters of each robot and the theoretical values. LeBai performs precise calibration of the actual DH parameters before each robot leaves the factory. Customers who need to perform visual grasping, offline simulation, and other applications can consult with developers for detailed information.

Singular Positions

There are three typical singular positions:

  1. Four axes parallel, i.e., the 2nd, 3rd, 4th, and 6th joints are in a parallel state.
  2. Zero position, i.e., when all joint angles of the robot are 0.
  3. When the robot arm is fully extended in any position

Four axes parallel

Zero position