lebai-motion-control  3.1.6
lebai motion control C interface
Data Structures | Typedefs | Functions
lmc_controller.h File Reference

Controller related functions. More...

#include <motion_control/lmc_robot_model.h>
#include <motion_control/lmc_joint.h>
Include dependency graph for lmc_controller.h:

Go to the source code of this file.

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 related functions.

Author
liufang
Date
2021-10-18

Definition in file lmc_controller.h.