lebai-motion-control  3.1.6
lebai motion control C interface
Data Structures | Typedefs | Functions
controller

Controller module. More...

Data Structures

struct  lmc_controller_cartesian_admittance_config
 Cartesian admiitance controler config data struct. More...
 

Typedefs

typedef struct lmc_controller lmc_controller_t
 Controller data structure, contain all the controller instance. More...
 
typedef struct lmc_controller_cartesian_admittance_config lmc_controller_cartesian_admittance_config_t
 Cartesian admiitance controler config data struct.
 

Functions

lmc_controller_tlmc_controller_new ()
 Create a controller data instance. More...
 
void lmc_controller_delete (lmc_controller_t **controller_addr)
 Delete a controller data instance. More...
 
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. More...
 
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. More...
 
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. More...
 
int lmc_controller_computed_torque_set_param (lmc_controller_t *const controller, const double *kp, const double *kv)
 Set computed torque control parameters. More...
 
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. More...
 
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. More...
 
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 limited by this value. More...
 
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, when force_mode is enabled, an loop is inserted after the trajectory_generator. More...
 
void lmc_controller_cartesian_admittance_request_end (lmc_controller_t *const controller)
 Cartesian admittance control block request end function for robot. More...
 
int lmc_controller_cartesian_admittance_activated (lmc_controller_t *const controller)
 Cartesian admittance control block activate state check function for robot. More...
 
void lmc_controller_cartesian_admittance_set_damping (lmc_controller_t *const controller, double d)
 Cartesian admittance control block set damping function. More...
 
void lmc_controller_cartesian_admittance_set_mass (lmc_controller_t *const controller, double mass)
 Cartesian admittance control block set mass function. More...
 
void lmc_controller_cartesian_admittance_set_force_threshold (lmc_controller_t *const controller, double threshold)
 Cartesian admittance control block set force threshold function. More...
 
void lmc_controller_cartesian_admittance_set_torque_threshold (lmc_controller_t *const controller, double threshold)
 Cartesian admittance control block set torque threshold function. More...
 
void lmc_controller_cartesian_admittance_set_dexterity (lmc_controller_t *const controller, size_t n)
 Cartesian admittance control block set dexterity function. More...
 
void lmc_controller_cartesian_admittance_cleanup (lmc_controller_t *const controller)
 Cartesian admittance control block cleanup function. More...
 

Detailed Description

Controller module.

Typedef Documentation

typedef struct lmc_controller lmc_controller_t

Controller data structure, contain all the controller instance.

The details of this data structure is hidden in c files. We do not use the structure member directly, try to use the API.

Definition at line 30 of file lmc_controller.h.

Function Documentation

int lmc_controller_cartesian_admittance_activated ( lmc_controller_t *const  controller)

Cartesian admittance control block activate state check function for robot.

Note
Parameters
[in]controllerController data structure for setting.
Returns
Return 1 for activated, 0 for not activated.
void lmc_controller_cartesian_admittance_cleanup ( lmc_controller_t *const  controller)

Cartesian admittance control block cleanup function.

Note
Call this function to force deactive admiitance control.
Usually called when emergency happend, in this case, you don't have to call update anymore.
Parameters
[in]controllerController data structure for setting.
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.

Note
Parameters
[in]controllerController data for controller computing.
[in]joint_cmdJoint trajectory set pos.
[in]configControl config.
void lmc_controller_cartesian_admittance_request_end ( lmc_controller_t *const  controller)

Cartesian admittance control block request end function for robot.

Note
Parameters
[in]controllerController data structure for setting.
void lmc_controller_cartesian_admittance_set_damping ( lmc_controller_t *const  controller,
double  d 
)

Cartesian admittance control block set damping function.

Note
Parameters
[in]controllerController data structure for setting.
[in]ddamping data. Default value is 100, max value is 5000, min value is 20.
void lmc_controller_cartesian_admittance_set_dexterity ( lmc_controller_t *const  controller,
size_t  n 
)

Cartesian admittance control block set dexterity function.

Note
The larger value may cause the robot faec a vibration, we
Parameters
[in]controllerController data structure for setting.
[in]ndexterity Default value is 10. Ranges are [1,10]. When we set a smaller value, it's more likely we face a singularity error. The larger the value is, the worksapce of robot in force mode is larger.
void lmc_controller_cartesian_admittance_set_force_threshold ( lmc_controller_t *const  controller,
double  threshold 
)

Cartesian admittance control block set force threshold function.

Note
Parameters
[in]controllerController data structure for setting.
[in]thresholdforce threshold. Default value is 10. if the total force (control force + external force ) is lesser than the threshold, zero force is computed for controller
void lmc_controller_cartesian_admittance_set_mass ( lmc_controller_t *const  controller,
double  mass 
)

Cartesian admittance control block set mass function.

Note
Parameters
[in]controllerController data structure for setting.
[in]massmass data. Default value is 10, max value is 1000, min value is 0.1, max vaule is 5000.
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 limited by this value.

Note
This function can be called in realtime to change the current base offset limit.
Parameters
[in]controllerController data for controller computing.
[in]minusminus diff limit.
[in]plusplus diff limit.
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.

Note
This function can be called in realtime to change the current task frame.
Parameters
[in]controllerController data for controller computing.
[in]task_frametask frame.
void lmc_controller_cartesian_admittance_set_torque_threshold ( lmc_controller_t *const  controller,
double  threshold 
)

Cartesian admittance control block set torque threshold function.

Note
Parameters
[in]controllerController data structure for setting.
[in]thresholdtorque threshold. Default value is 0.1. if the total torque (control torque + external torque ) is lesser than the threshold, zero torque is computed for controller
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, when force_mode is enabled, an loop is inserted after the trajectory_generator.

force_mode.png

When the force_mode is enabled, the update function output a joint pos offset based on tg output.
When the force_mode is disabled, the update function output joint pos offset is always zero.

Note
Parameters
[in]controllerController data structure for setting.
[in]in_joint_cmdJoint command data input for compute, usually use the trajectory generator command data.
[in]in_joint_stateJoint state data input for compute.
[in]in_external_forceExternal force on tcp point in base coordinate. If there is no external sensor to measure the force, try to use lmc_dyn_update_tcp_force_direct_estimation or lmc_dyn_update_tcp_force_momentum_observer_estimation to get an estimate tcp force.
[out]out_joint_pos_offsetThe joint pos offset due to the admittance control, the offset is based on pos_cmd in in_joint_cmd.
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.

Note
Parameters
[in]controllerController data for controller computing.
[in]in_joint_stateJoint state data input for compute.
[in]in_joint_cmdJoint command data input for compute.
[out]out_torqueThe torque computing result.
[out]out_inertiaThe computed matrix principal diagonal inertia, mostly represent joint inertia state.
int lmc_controller_computed_torque_set_param ( lmc_controller_t *const  controller,
const double *  kp,
const double *  kv 
)

Set computed torque control parameters.

Note
In old lebai_kdl, we set these parameter in init function. Now we use this standalone api.
Parameters
[in]controllerController data structure for setting.
[in]kpkp array data.
[in]kvkv array data.
Returns
Return 0 on success, otherwise failure.
void lmc_controller_delete ( lmc_controller_t **  controller_addr)

Delete a controller data instance.

Note
The pointer will be set to NULL
Parameters
[in]controller_addrthe address of the trajectory generator pointer.
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.

Note
Parameters
[in]controllerController data for controller computing.
[in]in_joint_stateJoint state data input for compute.
[out]out_joint_torque_cmdThe computed result joint torque command for gravity compensation in array form.
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.

Note
Should be called before any use of controller function.
Parameters
[in]controllerController data.
[in]robot_modelRobot model data.
[in]cycle_timeCycle time of controll loop.
Returns
Return 0 on success, otherwise failed.
lmc_controller_t* lmc_controller_new ( )

Create a controller data instance.

Note
Controller is a data structure contains all the controller instance. It's a core data structure to many controller block procedure. Controller data must be inited by calling lmc_controller_init before any usage.