C, C++:
Algorithm Interface Configurationalgo
For the RealMan robotic arm, there are tool interfaces such as forward and inverse kinematics and various pose parameter transformations.
Initialize algorithm dependency data rm_algo_init_sys_data()
- Method prototype:
void rm_algo_init_sys_data(rm_robot_arm_model_e Mode,rm_force_type_e Type)
Jump to [rm_robot_arm_model_e](../type/typeList.md#rm_robot_arm_model_e_robotic arm model) and [rm_force_type_e](../type/typeList.md#rm_force_type_e_end force sensor type) for details of types
Note: Call it when no robotic arm is connected
- Parameter description:
Parameter | Type | Description |
---|---|---|
Model | Input | Robotic arm model. |
Type | Input | Sensor type. |
- Usage demo
rm_robot_arm_model_e Mode = RM_MODEL_RM_75_E;
rm_force_type_e Type = RM_MODEL_RM_SF_E;
rm_algo_init_sys_data(Mode, Type);
Get the algorithm library version number rm_algo_version()
- Method prototype:
char* rm_algo_version(void);
- Return value:
Parameter | Type | Description |
---|---|---|
- | str | Algorithm library version number. |
- Usage demo
char *version = rm_algo_version();
printf("current algo version: %s\n", version);
Set the mounting angle rm_algo_set_angle()
- Method prototype:
void rm_algo_set_angle(float x,float y,float z)
- Parameter description:
Parameter | Type | Description |
---|---|---|
x | Input | X-axis mounting angle, in °. |
y | Input | Y-axis mounting angle, in °. |
z | Input | Z-axis mounting angle, in °. |
- Usage demo
rm_algo_set_angle(0, 90, 0)
Get the mounting angle rm_algo_get_angle()
- Method prototype:
void rm_algo_get_angle(float x,float y,float z)
- Parameter description:
Parameter | Type | Description |
---|---|---|
x | Output | X-axis mounting angle, in °. |
y | Output | Y-axis mounting angle, in °. |
z | Output | Z-axis mounting angle, in °. |
- Usage demo
float x,y,z;
rm_algo_get_angle(&x,&y,&z);
Set the work frame rm_algo_set_workframe()
- Method prototype:
void rm_algo_set_workframe(const rm_frame_t *const coord_work)
Jump to rm_frame_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
coord_work | Input | Frame data (no name setting is required). |
- Usage demo
rm_frame_t coord_work;
coord_work.pose.position.x = (float)0.1;
coord_work.pose.position.y = (float)0.2;
coord_work.pose.position.z = (float)0.3;
coord_work.pose.euler.rx = (float)0.1;
coord_work.pose.euler.ry = (float)0.2;
coord_work.pose.euler.rz = (float)0.3;
rm_algo_set_workframe(&coord_work);
Get the current work frame rm_algo_get_curr_workframe()
- Method prototype:
void rm_algo_get_curr_workframe(rm_frame_t * coord_work)
Jump to rm_frame_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
coord_work | Output | Current work frame (obtained frame parameters, excluding frame name). |
- Usage demo
rm_frame_t coord_work;
rm_algo_get_curr_workframe(&coord_work);
Set the tool frame rm_algo_set_toolframe()
- Method prototype:
void rm_algo_set_toolframe(const rm_frame_t *const coord_tool)
Jump to rm_frame_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
coord_tool | Input | Frame data. |
- Usage demo
rm_frame_t coord_tool;
coord_tool.pose.position.x = (float)0.1;
coord_tool.pose.position.y = (float)0.2;
coord_tool.pose.position.z = (float)0.3;
coord_tool.pose.euler.rx = (float)0.1;
coord_tool.pose.euler.ry = (float)0.2;
coord_tool.pose.euler.rz = (float)0.3;
coord_tool.payload = (float)1.5;
coord_tool.x = (float)0.1;
coord_tool.y = (float)0.2;
coord_tool.z = (float)0.3;
rm_algo_set_toolframe(&coord_tool);
Get the current tool frame rm_algo_get_curr_toolframe()
- Method prototype:
void rm_algo_get_curr_toolframe(rm_frame_t * coord_tool)
Jump to rm_frame_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
coord_tool | Output | Current tool frame. |
- Usage demo
rm_frame_t coord_tool;
rm_algo_get_curr_toolframe(&coord_tool);
Set maximum joint limit rm_algo_set_joint_max_limit()
- Method prototype:
void rm_algo_set_joint_max_limit(const float *const joint_limit)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_limit | Input | Maximum angle limit, in °. |
- Usage demo
float joint_limit[6] = {150,100,90,120,120,300};
rm_algo_set_joint_max_limit(joint_limit);
Get maximum joint limit rm_algo_get_joint_max_limit()
- Method prototype:
void rm_algo_get_joint_max_limit(float * joint_limit)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_limit | Output | Return the maximum joint limit. |
- Usage demo
float after_joint_limit[7];
rm_algo_get_joint_max_limit(after_joint_limit);
Set minimum joint limit rm_algo_set_joint_min_limit()
- Method prototype:
void rm_algo_set_joint_min_limit(const float *const joint_limit)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_limit | Input | Minimum angle limit, in °. |
- Usage demo
float joint_limit[6] = {150,100,90,120,120,300};
rm_algo_set_joint_min_limit(joint_limit);
Get minimum joint limit rm_algo_get_joint_min_limit()
- Method prototype:
void rm_algo_get_joint_min_limit(const float *const joint_limit)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_limit | Output | Save the returned minimum joint limit. |
- Usage demo
float after_joint_limit[7];
rm_algo_get_joint_min_limit(after_joint_limit);
Set maximum joint speed rm_algo_set_joint_max_speed()
- Method prototype:
void rm_algo_set_joint_max_speed(const float *const joint_slim_max)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_slim_max | Input | Maximum speed, in RPM. |
- Usage demo
float joint_slim_max[6] = {20,20,20,20,20,20};
rm_algo_set_joint_max_speed(joint_slim_max);
Get maximum joint speed rm_algo_get_joint_max_speed()
- Method prototype:
void rm_algo_get_joint_max_speed(float * joint_slim_max)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_slim_max | Output | Save the returned maximum speed, in RPM. |
- Usage demo
float after_joint_slimit_max[6];
rm_algo_get_joint_max_speed(after_joint_slimit_max);
Set maximum joint acceleration rm_algo_set_joint_max_acc()
- Method prototype:
void rm_algo_set_joint_max_acc(const float *const joint_alim_max)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_alim_max | Input | Maximum acceleration, in RPM/s. |
- Usage demo
float joint_alimit[6] = {20,20,20,20,20,20};
rm_algo_set_joint_max_acc(joint_alimit);
Get maximum joint acceleration rm_algo_get_joint_max_acc()
- Method prototype:
void rm_algo_get_joint_max_acc(float * joint_alim_max)
- Parameter description:
Parameter | Type | Description |
---|---|---|
joint_alim_max | Output | Save the returned maximum acceleration, in RPM/s. |
- Usage demo
float after_joint_alimit[6];
rm_algo_get_joint_max_acc(after_joint_alimit);
Set the inverse kinematics solution mode rm_algo_set_redundant_parameter_traversal_mode()
- Method prototype:
void rm_algo_set_redundant_parameter_traversal_mode(bool mode);
- Parameter description:
Parameter | Type | Description |
---|---|---|
mode | Input | - true: traversal mode, redundant parameter traversal solution strategy. It is applicable to scenes where the current pose differs greatly from the required pose, such as MOVJ_P and pose editing, and it takes a long time. -false: single step mode, automatically adjusting the solution strategy of redundant parameters. It is applicable to scenes where the difference between the current pose and the required pose is very small and continuous cycle control is required, such as the pose solution of Cartesian space planning, and it takes a short time. |
- Usage demo
// Set the inverse solution solving mode to the traversal mode
rm_algo_set_redundant_parameter_traversal_mode(true);
Inverse kinematics function rm_algo_inverse_kinematics()
- Method prototype:
int rm_algo_inverse_kinematics(rm_robot_handle * handle,rm_inverse_kinematics_params_t params,float * q_out)
Jump to rm_robot_handle and rm_inverse_kinematics_params_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
params | Input | Inverse kinematics input parameter structure. |
q_out | Output | Output joint angle, in °. |
- Return value:
Parameter | Type | Description |
---|---|---|
0 | int | Inverse kinematics succeeds. |
1 | int | Inverse kinematics fails. |
-1 | int | The previous joint angle input is NULL. |
-2 | int | The target pose quaternion is invalid. |
Note:
- When the robotic arm is connected, the interface can be directly called for computation, and the parameters used for computation are the current parameters of the robotic arm.
- When the robotic arm is not connected, it is required to call the initialize algorithm dependence data interface first, set the frame, installation mode, joint speed, position, and other limits according to the actual requirements (if no settings are made, the computation is based on the factory defaults), and then set the control handle of the robotic arm to NULL.
- Usage demo
rm_inverse_kinematics_params_t params;
float joint_angles[6] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f};
float q_in[6] = {0.5f, 1.0f, 1.5f, 2.0f, 2.5f, 3.0f};
params.q_in = q_in;
params.q_pose.position.x = (float)0.3;
params.q_pose.position.y = (float)0.0;
params.q_pose.position.z = (float)0.3;
params.q_pose.quaternion.w = (float)0.0;
params.q_pose.quaternion.x = (float)0.0;
params.q_pose.quaternion.y = (float)0.0;
params.q_pose.quaternion.z = (float)0.0;
params.q_pose.euler.rx = (float)3.14;
params.q_pose.euler.ry = (float)0.0;
params.q_pose.euler.rz = (float)0.0;
params.flag = 1;
int result = wrapper.rm_algo_inverse_kinematics(handle, params, joint_angles);
printf("Inverse kinematics calculation: %d\n", result);
if (result == 0) {
printf("Joint angles: [%.2f, %.2f, %.2f, %.2f, %.2f, %.2f]\n", joint_angles[0], joint_angles[1], joint_angles[2], joint_angles[3], joint_angles[4], joint_angles[5]);
}
Forward kinematics algorithm rm_algo_forward_kinematics()
- Method prototype:
rm_pose_t rm_algo_forward_kinematics(rm_robot_handle * handle,const float *const joint)
Jump to rm_pose_t and rm_robot_handle for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle, which is required when the robotic arm is connected, and NULL when the robotic arm is not connected. |
joint | Input | Joint angle, in °. |
- Return value:
rm_pose_t Target pose, including information about the robotic arms x, y, z, rx, ry, rz.
Note:
- When the robotic arm is connected, the interface can be directly called for computation, and the parameters used for computation are the current parameters of the robotic arm.
- When the robotic arm is not connected, it is required to call the initialize algorithm dependence data interface first, set the frame, installation mode, joint speed, position, and other limits according to the actual requirements (if no settings are made, the computation is based on the factory defaults), and then set the control handle of the robotic arm to NULL.
- Usage demo
float joint_angles[6] = {0.5f, 1.0f, 1.5f, 2.0f, 2.5f, 3.0f};
rm_pose_t pose = rm_algo_forward_kinematics(handle, joint_angles);
printf("Joint angles: [%.2f, %.2f, %.2f, %.2f, %.2f, %.2f]\n", joint_angles[0], joint_angles[1],
joint_angles[2], joint_angles[3], joint_angles[4], joint_angles[5]);
printf("End effector pose: Position(%.2f, %.2f, %.2f), Quaternion(%.2f, %.2f, %.2f, %.2f), Euler angles(%.2f, %.2f, %.2f)\n",
pose.position.x, pose.position.y, pose.position.z,
pose.quaternion.w, pose.quaternion.x, pose.quaternion.y, pose.quaternion.z,
pose.euler.rx, pose.euler.ry, pose.euler.rz);
Euler angle to quaternion rm_algo_euler2quaternion()
- Method prototype:
rm_quat_t rm_algo_euler2quaternion(rm_euler_t eu)
Jump to rm_quat_t and rm_euler_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
eu | Input | Euler angle, in rad. |
- Return value:
Return the quaternion in the structure rm_quat_t.
- Usage demo
rm_euler_t euler = {(float)0.1, (float)0.2, (float)0.3};
rm_quat_t quat = rm_algo_euler2quaternion(euler);
printf("Euler angles: (rx: %.2f, ry: %.2f, rz: %.2f)\n", euler.rx, euler.ry, euler.rz);
printf("Quaternion: (w: %.2f, x: %.2f, y: %.2f, z: %.2f)\n", quat.w, quat.x, quat.y, quat.z);
Quaternion to Euler angle rm_algo_quaternion2euler()
- Method prototype:
rm_euler_t rm_algo_quaternion2euler(rm_quat_t qua)
Jump to rm_quat_t and rm_euler_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
qua | Input | Quaternion. |
- Return value:
Return the Euler angle in the structure rm_euler_t.
- Usage demo
rm_quat_t quat = {(float)1.0, (float)0.0, (float)0.0, (float)0.0};
rm_euler_t euler = rm_algo_quaternion2euler(quat);
printf("Quaternion: (w: %.2f, x: %.2f, y: %.2f, z: %.2f)\n", quat.w, quat.x, quat.y, quat.z);
printf("Euler angles: (rx: %.2f, ry: %.2f, rz: %.2f)\n", euler.rx, euler.ry, euler.rz);
Euler angle to rotation matrix rm_algo_euler2matrix()
- Method prototype:
rm_matrix_t rm_algo_euler2matrix(rm_euler_t state)
Jump to rm_matrix_t and rm_euler_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
state | Input | Euler angle, in rad. |
- Return value:
Return the rotation matrix in the structure rm_euler_t.
- Usage demo
//Euler angle to rotation matrix
rm_euler_t eu;
rm_matrix_t matrix;
eu.rx = -2.85993f;
eu.ry = -0.447394f;
eu.rz = -1.81038f;
matrix = rm_algo_euler2matrix(eu);
Pose to rotation matrix rm_algo_pos2matrix()
- Method prototype:
rm_matrix_t rm_algo_pos2matrix(rm_pose_t state)
Jump to rm_matrix_t and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
state | Input | Pose. |
- Return value:
Return the rotation matrix in the structure rm_matrix_t.
- Usage demo
rm_pose_t pose;
rm_matrix_t matrix;
pose.position.x = -0.177347f;
pose.position.y = 0.438112f;
pose.position.z = -0.215102f;
pose.euler.rx = 2.09078f;
pose.euler.ry = 0.942362f;
pose.euler.rz = 2.39144f;
matrix = rm_algo_pos2matrix(pose);
Rotation matrix to pose rm_algo_matrix2pos()
- Method prototype:
rm_pose_t rm_algo_matrix2pos(rm_matrix_t matrix)
Jump to rm_matrix_t and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
matrix | Input | Rotation matrix. |
- Return value:
Return the pose in the structure rm_pose_t.
- Usage demo
rm_matrix_t matrix;
matrix.irow = 4;
matrix.iline = 4;
float point[4][4] = {{1.0, 0.0, 0.0, 10.0},{0.0, 1.0, 0.0, 20.0},{0.0, 0.0, 1.0, 30.0},{0.0, 0.0, 0.0, 1.0}};
for(int i = 0; i < 4; i++){
for(int j = 0; j < 4; j++){
matrix.data[i][j] = point[i][j];
}
};
rm_pose_t pose = rm_algo_matrix2pos(matrix);
Base frame to work frame rm_algo_base2workframe()
- Method prototype:
rm_pose_t rm_algo_base2workframe(rm_matrix_t matrix,rm_pose_t state)
Jump to rm_matrix_t and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
matrix | Input | Matrix of the work frame in the base frame. |
state | Input | Pose of the end frame in the base frame. |
- Return value:
Return the pose in the structure [rm_pose_t](.. /struct/pose), indicating the pose of the base frame in the work frame.
- Usage demo
rm_matrix_t matrix = {
4, 4,
{
{1.0, 0.0, 0.0, 0.1},
{0.0, 1.0, 0.0, 0.2},
{0.0, 0.0, 1.0, 0.3},
{0.0, 0.0, 0.0, 1.0}
}
};
rm_pose_t state = {
{0.5, 0.5, 0.5}, // Position
.euler = {0.1, 0.2, 0.3} // Euler angle
};
rm_matrix_t matrix = Algo_Pos2Matrix(pose1);
pose = rm_algo_base2workframe(matrix,pose1);
printf("POSE: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );
Work frame to base framerm_algo_workframe2base()
- Method prototype:
rm_pose_t rm_algo_workframe2base(rm_matrix_t matrix,rm_pose_t state)
Jump to rm_matrix_t and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
matrix | Input | Matrix of the work frame in the base frame. |
state | Input | Pose of the end frame in the base frame. |
- Return value:
Return the pose in the structure rm_pose_t, indicating the pose of the work frame in the base frame.
- Usage demo
rm_matrix_t matrix = {
4, 4,
{
{1.0, 0.0, 0.0, 0.1},
{0.0, 1.0, 0.0, 0.2},
{0.0, 0.0, 1.0, 0.3},
{0.0, 0.0, 0.0, 1.0}
}
};
rm_pose_t state = {
{0.5, 0.5, 0.5}, // Position
.euler = {0.1, 0.2, 0.3} // Euler angle
};
pose = rm_algo_workframe2base(matrix,state);
printf("POSE: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );
Compute the pose in rotational movement rm_algo_RotateMove()
- Method prototype:
rm_pose_t rm_algo_RotateMove(rm_robot_handle * handle,const float *const curr_joint,int rotate_axis,float rotate_angle,rm_pose_t choose_axis)
Jump to rm_robot_handle and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
curr_joint | Input | Current joint angle, in °. |
rotate_axis | Input | Rotation axis, 1: X-axis, 2: Y-axis, 3: Z-axis. |
rotate_angle | Input | Rotation angle, in °. |
choose_axis | Input | Specify the frame for computation. |
- Return value:
Return the pose in the structure rm_pose_t.
- Usage demo
// Compute the pose after rotating 10° around the X-axis in the frame
float joint[6] = {0,0,90,0,90,0};
rm_pose_t frame;
frame.position.x=0;
frame.position.y=0;
frame.position.z=0;
frame.euler.rx = 0;
frame.euler.ry = 0;
frame.euler.rz = 0;
rm_pose_t pose;
float rotateAngle = 10;
pose = Algo_RotateMove(joint,1,rotateAngle ,frame);
printf("POSE: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );
Compute the pose in movement along the tool frame rm_algo_cartesian_tool()
- Method prototype:
rm_pose_t rm_algo_cartesian_tool(rm_robot_handle * handle,const float *const curr_joint,float move_lengthx,float move_lengthy,float move_lengthz)
Jump to rm_robot_handle and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
curr_joint | Input | Current joint angle, in °. |
move_lengthx | Input | Movement length along the X-axis, in m. |
move_lengthy | Input | Movement length along the Y-axis, in m. |
move_lengthz | Input | Movement length along the Z-axis, in m. |
- Return value:
Return the pose in the structure rm_pose_t, indicating the pose in the work frame.
- Usage demo
float joint[6] = {20,20,70,30,90,120};
rm_pose_t pose = rm_algo_cartesian_tool(joint,0.01f,0.01f,0.01f);
printf("POSE: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );
Compute the pose after Pos and Rot have a displacement and rotation angle along a frame rm_algo_cartesian_tool()
- Method prototype:
rm_pose_t rm_algo_PoseMove(rm_robot_handle *handle,rm_pose_t poseCurrent, const float *deltaPosAndRot, int frameMode);
Jump to rm_robot_handle and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
poseCurrent | Input | Current pose (represented by the Euler angle). |
deltaPosAndRot | Input | Position and rotation array, where position in m and rotation in °. |
frameMode | Input | Frame mode selection, 0: work (any frame is available), 1: tool. |
- Return value:
Return the pose in the structure rm_pose_t, indicating the pose after translation and rotation.
- Usage demo
// Use the current angle to get the current pose through forward kinematics
float joint[6] = {0,-30,90,30,90,0, 0};
rm_pose_t target = rm_algo_forward_kinematics(handle, joint);
// Compute the pose after the movement
rm_pose_t afterPosAndRot;
float deltaPosAndRot[6] = {0.01,0.01,0.01,20,20,20};
afterPosAndRot = rm_algo_PoseMove(target, deltaPosAndRot,1);
printf("POSE: %f, %f, %f, %f, %f, %f\n",afterPosAndRot.position.x,afterPosAndRot.position.y,afterPosAndRot.position.z,afterPosAndRot.euler.rx ,afterPosAndRot.euler.ry ,afterPosAndRot.euler.rz );
End pose to tool pose rm_algo_end2tool()
- Method prototype:
rm_pose_t rm_algo_end2tool(rm_robot_handle * handle,rm_pose_t eu_end)
Jump to rm_robot_handle and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
eu_end | Input | End pose based on world frame and default tool frame. |
- Return value:
Return the pose in the structure rm_pose_t, indicating the end pose based on the work frame and tool frame.
- Usage demo
rm_pose_t pose;
rm_pose_t eu_end;
eu_end.position.x = -0.259256f;
eu_end.position.y = -0.170727f;
eu_end.position.z = 0.35621f;
eu_end.euler.rx = -2.85993f;
eu_end.euler.ry = -0.447394f;
eu_end.euler.rz = -1.81038f;
pose = rm_algo_end2tool(eu_end);
printf("Pose: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );
Tool pose to end pose rm_algo_tool2end()
- Method prototype:
rm_pose_t rm_algo_tool2end(rm_robot_handle * handle,rm_pose_t eu_tool)
Jump to rm_robot_handle and rm_pose_t for details of the structure
- Parameter description:
Parameter | Type | Description |
---|---|---|
handle | Input | Robotic arm control handle. |
eu_tool | Input | End pose based on work frame and tool frame. |
- Return value:
Return the pose in the structure rm_pose_t, indicating the end pose based on the world frame and default tool frame.
- Usage demo
rm_pose_t pose;
rm_pose_t eu_tool;
eu_tool.position.x = -0.17391f;
eu_tool.position.y = 0.437109f;
eu_tool.position.z = -0.21619f;
eu_tool.euler.rx = 2.741f;
eu_tool.euler.ry = -0.244002f;
eu_tool.euler.rz = 2.938f;
pose = rm_algo_end2tool(eu_tool);
printf("POSE: %f, %f, %f, %f, %f, %f\n",pose.position.x,pose.position.y,pose.position.z,pose.euler.rx ,pose.euler.ry ,pose.euler.rz );