lebai-motion-control  3.1.6
lebai motion control C interface
lmc_dyn.h
Go to the documentation of this file.
1 
7 #ifndef LMC_DYN
8 #define LMC_DYN
11 
12 
13 
14 
15 #ifdef __cplusplus
16 extern "C" {
17 #endif /* __cplusplus */
18 
34 int lmc_dyn_id(lmc_robot_model_t * const robot_model, lmc_joint_state_t const * const joint_state,
35 double * const torque);
36 
46 int lmc_dyn_update_tcp_force_direct_estimation(lmc_robot_model_t * const robot_model, lmc_joint_state_t const * const joint_state,
47 double const* const torque, lmc_wrench_t* const f);
48 
49 
60 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,
61 double const* const torque, lmc_wrench_t* const f);
62 
70 int lmc_dyn_init_tcp_force_momentum_observer_estimation(lmc_robot_model_t * const robot_model, lmc_joint_state_t const * const joint_state);
71 
81 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);
82 
83 
84 
94 
107 
117 
118 
119 
127 int lmc_dyn_set_gravity(lmc_robot_model_t const * const robot_model, lmc_translation_t const * const gravity);
128 
132 #ifdef __cplusplus
133 }
134 #endif /* __cplusplus */
135 
136 #endif /* LMC_DYN */
Cartesian translation coordinate.
Definition: lmc_math.h:29
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.
Transform force representation.
Definition: lmc_math.h:106
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 joi...
Joint related data structure.
struct lmc_robot_model lmc_robot_model_t
Robot model data structure.
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.
joint state data
Definition: lmc_joint.h:21
All sample joint state data.
Definition: lmc_joint.h:54
*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.
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 pos...
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.
Robot model related data structures and functions.