lebai-motion-control  3.1.6
lebai motion control C interface
lmc_controller.h
Go to the documentation of this file.
1 
7 #ifndef LMC_CONTROLLER
8 #define LMC_CONTROLLER
11 
12 #ifdef __cplusplus
13 extern "C"
14 {
15 #endif /* __cplusplus */
16 
30  typedef struct lmc_controller lmc_controller_t;
31 
36  {
38  unsigned int selection_vector[6];
40  unsigned int type;
41  double limits[6];
43 
52 
58  void lmc_controller_delete(lmc_controller_t **controller_addr);
59 
68  int lmc_controller_init(lmc_controller_t *const controller, lmc_robot_model_t const *const robot_model,
69  double const cycle_time);
70 
78  int lmc_controller_gravity_compensate(lmc_controller_t *const controller, lmc_joint_state_t const *const in_joint_state,
79  double *const out_joint_torque_cmd);
80 
91  lmc_joint_state_t const *const in_joint_state, lmc_joint_cmd_t const *const in_joint_cmd,
92  double *const out_torque, double *const out_inertia);
93 
102  int lmc_controller_computed_torque_set_param(lmc_controller_t *const controller, const double *kp, const double *kv);
103 
111  void lmc_controller_cartesian_admittance_config(lmc_controller_t *const controller, lmc_joint_cmd_t const *const joint_cmd, lmc_controller_cartesian_admittance_config_t const *const config);
112 
120 
128  void lmc_controller_cartesian_admittance_set_offset_limit(lmc_controller_t *const controller, lmc_twist_t const *const minus, lmc_twist_t const *const plus);
129 
130 
145  int lmc_controller_cartesian_admittance_update(lmc_controller_t *const controller, lmc_joint_cmd_t const *const in_joint_cmd, lmc_joint_state_t const *const in_joint_state, lmc_wrench_t const * const in_external_force, double * const out_joint_pos_offset);
146 
153 
161 
168  void lmc_controller_cartesian_admittance_set_damping(lmc_controller_t *const controller, double d);
169 
176  void lmc_controller_cartesian_admittance_set_mass(lmc_controller_t *const controller, double mass);
177 
184  void lmc_controller_cartesian_admittance_set_force_threshold(lmc_controller_t *const controller, double threshold);
191  void lmc_controller_cartesian_admittance_set_torque_threshold(lmc_controller_t *const controller, double threshold);
192 
202 
210 
211 
214 #ifdef __cplusplus
215 }
216 #endif /* __cplusplus */
217 
218 #endif /* LMC_CONTROLLER */
void lmc_controller_cartesian_admittance_set_offset_limit(lmc_controller_t *const controller, lmc_twist_t const *const minus, lmc_twist_t const *const plus)
Cartesian admittance controll set base offset limit, the diff twist due to admittance control will be...
void lmc_controller_delete(lmc_controller_t **controller_addr)
Delete a controller data instance.
void lmc_controller_cartesian_admittance_set_force_threshold(lmc_controller_t *const controller, double threshold)
Cartesian admittance control block set force threshold function.
void lmc_controller_cartesian_admittance_cleanup(lmc_controller_t *const controller)
Cartesian admittance control block cleanup function.
int lmc_controller_cartesian_admittance_update(lmc_controller_t *const controller, lmc_joint_cmd_t const *const in_joint_cmd, lmc_joint_state_t const *const in_joint_state, lmc_wrench_t const *const in_external_force, double *const out_joint_pos_offset)
Cartesian admittance control block update function for robot. As in the following picture...
void lmc_controller_cartesian_admittance_set_torque_threshold(lmc_controller_t *const controller, double threshold)
Cartesian admittance control block set torque threshold function.
struct lmc_controller_cartesian_admittance_config lmc_controller_cartesian_admittance_config_t
Cartesian admiitance controler config data struct.
void lmc_controller_cartesian_admittance_config(lmc_controller_t *const controller, lmc_joint_cmd_t const *const joint_cmd, lmc_controller_cartesian_admittance_config_t const *const config)
Cartesian admittance controll block config function for robot.
void lmc_controller_cartesian_admittance_request_end(lmc_controller_t *const controller)
Cartesian admittance control block request end function for robot.
Transform velocity representation.
Definition: lmc_math.h:96
joint command data
Definition: lmc_joint.h:35
lmc_controller_t * lmc_controller_new()
Create a controller data instance.
void lmc_controller_cartesian_admittance_set_task_frame(lmc_controller_t *const controller, lmc_transform_t const *const task_frame)
Cartesian admittance controll block set task frame.
Transform force representation.
Definition: lmc_math.h:106
int lmc_controller_init(lmc_controller_t *const controller, lmc_robot_model_t const *const robot_model, double const cycle_time)
Init a controller data.
struct lmc_controller lmc_controller_t
Controller data structure, contain all the controller instance.
Joint related data structure.
int lmc_controller_computed_torque(lmc_controller_t *const controller, lmc_joint_state_t const *const in_joint_state, lmc_joint_cmd_t const *const in_joint_cmd, double *const out_torque, double *const out_inertia)
Computed torque control block for robot.
Cartesian admiitance controler config data struct.
struct lmc_robot_model lmc_robot_model_t
Robot model data structure.
void lmc_controller_cartesian_admittance_set_dexterity(lmc_controller_t *const controller, size_t n)
Cartesian admittance control block set dexterity function.
int lmc_controller_gravity_compensate(lmc_controller_t *const controller, lmc_joint_state_t const *const in_joint_state, double *const out_joint_torque_cmd)
Compute gravity compensation block for robot, can be used for teaching.
joint state data
Definition: lmc_joint.h:21
Transform representation.
Definition: lmc_math.h:86
void lmc_controller_cartesian_admittance_set_damping(lmc_controller_t *const controller, double d)
Cartesian admittance control block set damping function.
int lmc_controller_cartesian_admittance_activated(lmc_controller_t *const controller)
Cartesian admittance control block activate state check function for robot.
void lmc_controller_cartesian_admittance_set_mass(lmc_controller_t *const controller, double mass)
Cartesian admittance control block set mass function.
int lmc_controller_computed_torque_set_param(lmc_controller_t *const controller, const double *kp, const double *kv)
Set computed torque control parameters.
Robot model related data structures and functions.