lebai-motion-control  3.1.6
lebai motion control C interface
Functions
lmc_dyn.h File Reference

Dynamic related functions. More...

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

Go to the source code of this file.

Functions

int lmc_dyn_id (lmc_robot_model_t *const robot_model, lmc_joint_state_t const *const joint_state, double *const torque)
 Compute inverse dynamic of robot: given the joint position, velocity and acceleration, compute the joint torque. More...
 
int lmc_dyn_update_tcp_force_direct_estimation (lmc_robot_model_t *const robot_model, lmc_joint_state_t const *const joint_state, double const *const torque, lmc_wrench_t *const f)
 Core update of direct dynamic equation based external tcp force estimatation algorithm: given the joint position, velocity and acceleration and current feedback torque on joint, try to estimate the external tcp force. More...
 
int lmc_dyn_update_tcp_force_momentum_observer_estimation (lmc_robot_model_t *const robot_model, double cycle_time, lmc_joint_state_t const *const joint_state, double const *const torque, lmc_wrench_t *const f)
 Core update of momentum observer based external tcp force estimatation algorithm: given the joint position, velocity and current feedback torque on joint, try to estimate the external tcp force. More...
 
int lmc_dyn_init_tcp_force_momentum_observer_estimation (lmc_robot_model_t *const robot_model, lmc_joint_state_t const *const joint_state)
 Init momentum observer estimation. More...
 
int lmc_dyn_estimate_payload_with_twice_strategy (lmc_robot_model_t *const robot_model, lmc_all_sampled_joint_state_t const *const all_sampled_data, double *const mass, lmc_translation_t *const com)
 Estimate payload parameter. More...
 
*int lmc_dyn_gravity_compensate (lmc_robot_model_t *const robot_model, lmc_joint_state_t const *const joint_state,*double *const torque)
 Compute gravity compensation for robot, can be used for teaching. More...
 
**int lmc_dyn_computed_torque_control (lmc_robot_model_t *const robot_model,*lmc_joint_state_t const *const joint_state, lmc_joint_cmd_t const *const joint_cmd,*double *const torque, double *const inertia)
 Computed torque control algorithm. More...
 
**int lmc_dyn_set_computed_torque_control_param (lmc_robot_model_t *const robot_model, const double *kp, const double *kv)
 Set computed torque control parameters. More...
 
*int lmc_dyn_set_gravity (lmc_robot_model_t const *const robot_model, lmc_translation_t const *const gravity)
 Set gravity vector, will affect all the dynamic algorithms. More...
 

Detailed Description

Dynamic related functions.

Author
liufang
Date
2021-07-11

Definition in file lmc_dyn.h.