lebai-motion-control  3.1.8
lebai motion control C interface
lmc_kin.h
Go to the documentation of this file.
1 
7 #ifndef LMC_KIN
8 #define LMC_KIN
10 #include <stdint.h>
11 
12 #ifdef __cplusplus
13 extern "C" {
14 #endif /* __cplusplus */
15 
33 int lmc_kin_fk_pose(lmc_robot_model_t* const robot_model,
34  double const* const joint_pos,
35  lmc_transform_t* const cart_pose);
36 
54 int lmc_kin_fk_pose_by_index(lmc_robot_model_t* const robot_model,
55  double const* const joint_pos, int index,
56  lmc_transform_t* const cart_pose);
57 
64 void lmc_kin_set_ik_coeff(lmc_robot_model_t* const robot_model,
65  double const* const coeff);
66 
76 int lmc_kin_ik_pose(lmc_robot_model_t* const robot_model,
77  lmc_transform_t const* const cart_pose,
78  double* const joint_pos);
79 
91 int lmc_kin_all_ik_poses(lmc_robot_model_t* const robot_model,
92  lmc_transform_t const* const cart_pose,
93  unsigned int* const num,
94  lmc_all_joint_poses_t* const joint_poses);
95 
107 double lmc_kin_manipulation_measure(lmc_robot_model_t* const robot_model,
108  double const* const joint_pos);
109 
136 int16_t lmc_kin_get_singularity_type(lmc_robot_model_t* const robot_model,
137  double const* const joint_pos);
138 
148 int lmc_kin_cal_translation(lmc_transform_t const* const all_cart_pose,
149  size_t size, float tol, lmc_translation_t* const t);
150 
166  lmc_translation_t const* const x,
167  lmc_translation_t const* const xy,
168  double tol, lmc_transform_t* const t);
169 
172 #ifdef __cplusplus
173 }
174 #endif /* __cplusplus */
175 
176 #endif /* LMC_KIN */
Cartesian translation coordinate.
Definition: lmc_math.h:29
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...
void lmc_kin_set_ik_coeff(lmc_robot_model_t *const robot_model, double const *const coeff)
Set the coefficient for computing the best solution of inverse kinematic.
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.
Transform representation.
Definition: lmc_math.h:86
Data structure to store all joint positions.
Definition: lmc_joint.h:45
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...