Cartesian translation coordinate.
int16_t lmc_kin_get_singularity_type(lmc_robot_model_t *const robot_model, double const *const joint_pos)
Compute singularity type data.
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).
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...
struct lmc_robot_model lmc_robot_model_t
Robot model data structure.
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.
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.
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.
Data structure to store all joint positions.
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...
Robot model related data structures and functions.
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 th...