Basic RT components and utilities
315.15.0
|
import"StabilizerService.idl";
Public Attributes | |
sequence< double > | ik_optional_weight_vector |
Joint weight for Inverse Kinematics calculation. 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... | |
unsigned short | ik_loop_count |
IK loop count. More... | |
double OpenHRP::StabilizerService::IKLimbParameters::avoid_gain |
Avoid joint limit gain for inverse kinematics.
unsigned short OpenHRP::StabilizerService::IKLimbParameters::ik_loop_count |
IK loop count.
sequence<double> OpenHRP::StabilizerService::IKLimbParameters::ik_optional_weight_vector |
Joint weight for Inverse Kinematics calculation.
double OpenHRP::StabilizerService::IKLimbParameters::manipulability_limit |
Manipulability limit for inverse kinematics.
double OpenHRP::StabilizerService::IKLimbParameters::reference_gain |
Reference joint angles tracking gain for inverse kinematics.
double OpenHRP::StabilizerService::IKLimbParameters::sr_gain |
SR-inverse gain for inverse kinematics.