lebai-motion-control  3.1.6
lebai motion control C interface
Functions
dynamics

Dynamics module. More...

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

Dynamics module.

Function Documentation

* * 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.

/**

  • *
    Note
  • Parameters
    [in]robot_modelRobot model data for dynamic computing.
  • Parameters
    [in]joint_stateJoint state data input for compute.
  • Parameters
    [in]joint_cmdJoint command data input for compute.
  • Parameters
    [out]torqueThe torque computing result.
  • Parameters
    [out]inertiaThe computed matrix principal diagonal inertia, mostly represent joint inertia state.
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.

Note
Maximun 1000 sample points.
Parameters
[in]robot_modelRobot model data for dynamic computing.
[in]all_sampled_dataAll sampled data. For joint torques, we get the delta torques of two measurements. Only one joint can move simultaneously.
[out]masscomputed mass.
[out]comcomputed center of mass.
Returns
Return 0 on success, otherwise failure.
* 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.

/**

  • *
    Note
  • Parameters
    [in]robot_modelRobot model data for dynamic computing.
  • Parameters
    [in]joint_stateJoint state data input for compute.
  • Parameters
    [out]torqueThe computed result in array form.
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.

Parameters
[in]robot_modelRobot model data for dynamic computing.
[in]joint_stateJoint state data input for compute.
[out]torqueThe computed result in array form.
Returns
Return 0 on success, otherwise failure.
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.

Note
This is a momentum observer based algorithm. this method must be called continously in every cycle.
Parameters
[in]robot_modelRobot model data for dynamic computing.
[in]joint_stateJoint state data input for compute, only position and velocity will be used.
Returns
Return 0 on success, otherwise failure.
* * 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.

/**

  • *
    Note
    In old lebai_kdl, we set these parameter in init function. Now we use this standalone api.
  • Parameters
    [in]robot_modelRobot model data structure for setting.
  • Parameters
    [in]kpkp array data.
  • Parameters
    [in]kvkv array data.
  • Returns
    Return 0 on success, otherwise failure.
* 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.

Note
Parameters
[in]robot_modelRobot model data structure for setting.
[in]gravitygravity vector data
Returns
Return 0 on success, otherwise failure.
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.

Note
This is a direct method using dynamic equation to estimate tcp force. Set vel and acc to zero in lmc_joint_state_t in case vel and acc data is not stable due to differential compute.
Parameters
[in]robot_modelRobot model data for dynamic computing.
[in]joint_stateJoint state data input for compute.
[in]torqueThe actual joint torque in array form.
[out]fThe external tcp force.
Returns
Return 0 on success, otherwise failure.
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.

Note
This is a momentum observer based algorithm. this method must be called continously in every cycle.
Parameters
[in]robot_modelRobot model data for dynamic computing.
[in]cycle_timeloop cycle time.
[in]joint_stateJoint state data input for compute, only position and velocity will be used.
[in]torqueThe actual joint torque in array form.
[out]fThe external tcp force.
Returns
Return 0 on success, otherwise failure.