lebai-motion-control  3.1.6
lebai motion control C interface
Functions
kinematics

Kinematics module. More...

Functions

int lmc_kin_fk_pose (lmc_robot_model_t *const robot_model, double const *const joint_pos, lmc_transform_t *const cart_pose)
 Compute kinematic forward TCP of robot. More...
 
int lmc_kin_fk_pose_by_index (lmc_robot_model_t *const robot_model, double const *const joint_pos, int index, lmc_transform_t *const cart_pose)
 Compute kinematic forward position of robot. This function can compute all the link position. More...
 
int lmc_kin_ik_pose (lmc_robot_model_t *const robot_model, lmc_transform_t const *const cart_pose, double *const joint_pos)
 Compute kinematic inverse joint position of robot. More...
 
int lmc_kin_all_ik_poses (lmc_robot_model_t *const robot_model, lmc_transform_t const *const cart_pose, unsigned int *const num, lmc_all_joint_poses_t *const joint_poses)
 Compute kinematic inverse all possible joint positions of robot. More...
 
double lmc_kin_manipulation_measure (lmc_robot_model_t *const robot_model, double const *const joint_pos)
 Compute manipulation measure. This function compute manipulation measure data, which indicate that the robot(manipulator) is in singularity. When the measure is less than 0.001, usually means the robot lose some ability in moving to certain direction. More...
 
int16_t lmc_kin_get_singularity_type (lmc_robot_model_t *const robot_model, double const *const joint_pos)
 Compute singularity type data. More...
 
int lmc_kin_cal_translation (lmc_transform_t const *const all_cart_pose, size_t size, float tol, lmc_translation_t *const t)
 Compute a transform from multi points(transform pose). More...
 
int lmc_kin_cal_transform_from_oxy (lmc_translation_t const *const o, lmc_translation_t const *const x, lmc_translation_t const *const xy, double tol, lmc_transform_t *const t)
 Calculate a transform from three points: origin point, point on x axis, and point on xy plane(but not on x axis). The calculated transform has a translation on origin point, and a rotation which x axis align to ox, y axis is on oxy plane and perpendicular to x axis, and z axis is perpendicular to oxy plane. More...
 

Detailed Description

Kinematics module.

Function Documentation

int lmc_kin_all_ik_poses ( lmc_robot_model_t *const  robot_model,
lmc_transform_t const *const  cart_pose,
unsigned int *const  num,
lmc_all_joint_poses_t *const  joint_poses 
)

Compute kinematic inverse all possible joint positions of robot.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing
[in]cart_poseCartesian pose for transform
[out]numNumber of total inverse kinematic solution.
[out]joint_posesArray of joint position array input as init pose.
Returns
Return 0 on success, otherwise failure.
int lmc_kin_cal_transform_from_oxy ( lmc_translation_t const *const  o,
lmc_translation_t const *const  x,
lmc_translation_t const *const  xy,
double  tol,
lmc_transform_t *const  t 
)

Calculate a transform from three points: origin point, point on x axis, and point on xy plane(but not on x axis). The calculated transform has a translation on origin point, and a rotation which x axis align to ox, y axis is on oxy plane and perpendicular to x axis, and z axis is perpendicular to oxy plane.

Parameters
[in]oOrigin point.
[in]xPoint on x axis.
[in]xyPoint on xy plane but not on x axis.
[in]tolTolerance for vector too small and parallel check. It's OK to set to 0.01.
[out]tresult transform.
Returns
Return 0 on success, otherwise failure.
int lmc_kin_cal_translation ( lmc_transform_t const *const  all_cart_pose,
size_t  size,
float  tol,
lmc_translation_t *const  t 
)

Compute a transform from multi points(transform pose).

Parameters
[in]all_cart_poseTranform data array
[in]sizenum of input transform data array
[in]tolTolerance for standard deviation computing, if any deviation exceed tolerance, the function returns error.
[out]tresult translation.
Returns
Return 0 on success, otherwise failure.
int lmc_kin_fk_pose ( lmc_robot_model_t *const  robot_model,
double const *const  joint_pos,
lmc_transform_t *const  cart_pose 
)

Compute kinematic forward TCP of robot.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing.
[in]joint_posJoint position array.
[out]cart_poseComputed cartesian pose.
Returns
Return 0 on success, otherwise failure.
int lmc_kin_fk_pose_by_index ( lmc_robot_model_t *const  robot_model,
double const *const  joint_pos,
int  index,
lmc_transform_t *const  cart_pose 
)

Compute kinematic forward position of robot. This function can compute all the link position.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing.
[in]joint_posJoint position array.
[in]indexlink index. The following list gives a detailed description:
  • -1: Always return the end effector(tcp) transform.
  • =0: Always return unit lmc_transform_t.
  • [1:segments_size+2]: Return the corresponding link transform. We have base_link->robot_link->tool_link structure. The segments_size is defined in lmc_robot_model_config.
  • >segments_size+2: fcuntion call failed and return error.
[out]cart_poseComputed cartesian pose.
Returns
Return 0 on success, otherwise failure.
int16_t lmc_kin_get_singularity_type ( lmc_robot_model_t *const  robot_model,
double const *const  joint_pos 
)

Compute singularity type data.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing
[in]joint_posJoint position array.
Returns
Return singulartity type data. The data is arranged by bitset:
Bit 16 ... Bit 3 Bit 2 Bit 1
NA NA Wrist Alignment Singularity Inner Workspace Limit Outer Workspace Limit

Outer Workspace Limit: This means the robot second link and third link are aligned, usually means the robot is almost reach its outside limitation.

outer_workspace_limit.png
Outer Workspace Limit

Inner Workspace Limit: This means the robot's flange end is close to the column directly above and below the robot base.

inner_workspace_limit.png
Inner Workspace Limit

Wrist Alignment Singularity: This means the robot's shoulder, elbow and wrist 1 joints all all align the movement of wrist joint 2.

wrist_alignment_singularity.png
Wrist Alignment Singularity
int lmc_kin_ik_pose ( lmc_robot_model_t *const  robot_model,
lmc_transform_t const *const  cart_pose,
double *const  joint_pos 
)

Compute kinematic inverse joint position of robot.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing
[in]cart_poseCartesian pose for transform
[in,out]joint_posJoint position array input as init pose, and then set to computed joint position.
Returns
Return 0 on success, otherwise failure.
double lmc_kin_manipulation_measure ( lmc_robot_model_t *const  robot_model,
double const *const  joint_pos 
)

Compute manipulation measure. This function compute manipulation measure data, which indicate that the robot(manipulator) is in singularity. When the measure is less than 0.001, usually means the robot lose some ability in moving to certain direction.

Note
Parameters
[in]robot_modelRobot model data for kinematic computing
[in]joint_posJoint position array.
Returns
Return manipulation measure value, you can use this return value to check singularity threshold by your self.