Basic RT components and utilities  315.7.0
Public Attributes | List of all members
OpenHRP::ImpedanceControllerService::impedanceParam Struct Reference

Impedance controller parameters for one end-effector. More...

import "ImpedanceControllerService.idl";

Public Attributes

double M_p
 Position mass [N/(m/s^2)]. More...
 
double D_p
 Position damper [N/(m/s)]. More...
 
double K_p
 Position spring [N/m]. More...
 
double M_r
 Rotation mass [Nm/(rad/s^2)]. More...
 
double D_r
 Rotation damper [N/(rad/s)]. More...
 
double K_r
 Rotation spring [N/rad]. More...
 
DblSequence3 force_gain
 Force gain (x,y,z). More...
 
DblSequence3 moment_gain
 Moment gain (x,y,z). More...
 
double sr_gain
 SR-inverse gain for inverse kinematics. More...
 
double avoid_gain
 Avoid joint limit gain for inverse kinematics. More...
 
double reference_gain
 Reference joint angles tracking gain for inverse kinematics. More...
 
double manipulability_limit
 Manipulability limit for inverse kinematics. More...
 
ControllerMode controller_mode
 Controller mode. More...
 
DblSequence ik_optional_weight_vector
 Joint weight for Inverse Kinematics calculation. More...
 
boolean use_sh_base_pos_rpy
 Use StateHolder basePos and baseRpy? More...
 

Detailed Description

Impedance controller parameters for one end-effector.

Member Data Documentation

double OpenHRP::ImpedanceControllerService::impedanceParam::avoid_gain

Avoid joint limit gain for inverse kinematics.

ControllerMode OpenHRP::ImpedanceControllerService::impedanceParam::controller_mode

Controller mode.

double OpenHRP::ImpedanceControllerService::impedanceParam::D_p

Position damper [N/(m/s)].

double OpenHRP::ImpedanceControllerService::impedanceParam::D_r

Rotation damper [N/(rad/s)].

DblSequence3 OpenHRP::ImpedanceControllerService::impedanceParam::force_gain

Force gain (x,y,z).

DblSequence OpenHRP::ImpedanceControllerService::impedanceParam::ik_optional_weight_vector

Joint weight for Inverse Kinematics calculation.

double OpenHRP::ImpedanceControllerService::impedanceParam::K_p

Position spring [N/m].

double OpenHRP::ImpedanceControllerService::impedanceParam::K_r

Rotation spring [N/rad].

double OpenHRP::ImpedanceControllerService::impedanceParam::M_p

Position mass [N/(m/s^2)].

double OpenHRP::ImpedanceControllerService::impedanceParam::M_r

Rotation mass [Nm/(rad/s^2)].

double OpenHRP::ImpedanceControllerService::impedanceParam::manipulability_limit

Manipulability limit for inverse kinematics.

DblSequence3 OpenHRP::ImpedanceControllerService::impedanceParam::moment_gain

Moment gain (x,y,z).

double OpenHRP::ImpedanceControllerService::impedanceParam::reference_gain

Reference joint angles tracking gain for inverse kinematics.

double OpenHRP::ImpedanceControllerService::impedanceParam::sr_gain

SR-inverse gain for inverse kinematics.

boolean OpenHRP::ImpedanceControllerService::impedanceParam::use_sh_base_pos_rpy

Use StateHolder basePos and baseRpy?


The documentation for this struct was generated from the following file: