Basic RT components and utilities  315.12.1
Public Attributes
OpenHRP::ImpedanceControllerService::impedanceParam Struct Reference

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

import "ImpedanceControllerService.idl";

List of all members.

Public Attributes

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

Detailed Description

Impedance controller parameters for one end-effector.


Member Data Documentation

Avoid joint limit gain for inverse kinematics.

Controller mode.

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

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

Force gain (x,y,z).

Joint weight for Inverse Kinematics calculation.

Position spring [N/m].

Rotation spring [N/rad].

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

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

Manipulability limit for inverse kinematics.

Moment gain (x,y,z).

Reference joint angles tracking gain for inverse kinematics.

SR-inverse gain for inverse kinematics.

Use StateHolder basePos and baseRpy?


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