Basic RT components and utilities
315.12.1
|
import "ImpedanceControllerService.idl";
Classes | |
struct | impedanceParam |
Impedance controller parameters for one end-effector. More... | |
Public Types | |
enum | ControllerMode { MODE_IDLE, MODE_IMP } |
Mode of controller. More... | |
typedef sequence< double, 3 > | DblSequence3 |
typedef double | DblArray3 [3] |
typedef sequence< double > | DblSequence |
typedef sequence< string > | StrSequence |
typedef sequence< sequence < double, 3 > > | Dbl3Sequence |
Public Member Functions | |
boolean | startImpedanceController (in string name) |
start impedance controller with waiting for transition. | |
boolean | startImpedanceControllerNoWait (in string name) |
start impedance controller without waiting for transition. | |
boolean | stopImpedanceController (in string name) |
stop impedance controller with waiting for transition. | |
boolean | stopImpedanceControllerNoWait (in string name) |
stop impedance controller without waiting for transition. | |
boolean | setImpedanceControllerParam (in string name, in impedanceParam i_param) |
set impedance parameters. | |
boolean | getImpedanceControllerParam (in string name, out impedanceParam i_param) |
get impedance parameters. | |
void | waitImpedanceControllerTransition (in string name) |
wait for impedance controller mode transition. |
typedef sequence<sequence<double, 3> > OpenHRP::ImpedanceControllerService::Dbl3Sequence |
typedef double OpenHRP::ImpedanceControllerService::DblArray3[3] |
typedef sequence<double> OpenHRP::ImpedanceControllerService::DblSequence |
typedef sequence<double, 3> OpenHRP::ImpedanceControllerService::DblSequence3 |
typedef sequence<string> OpenHRP::ImpedanceControllerService::StrSequence |
boolean OpenHRP::ImpedanceControllerService::getImpedanceControllerParam | ( | in string | name, |
out impedanceParam | i_param | ||
) |
get impedance parameters.
i_param | ouput impedance parameters |
name | impedance controller param's name, which basically corresponds to force sensor name |
boolean OpenHRP::ImpedanceControllerService::setImpedanceControllerParam | ( | in string | name, |
in impedanceParam | i_param | ||
) |
set impedance parameters.
i_param | input new impedance parameters |
name | impedance controller param's name, which basically corresponds to force sensor name |
boolean OpenHRP::ImpedanceControllerService::startImpedanceController | ( | in string | name | ) |
start impedance controller with waiting for transition.
name | impedance controller param's name, which basically corresponds to force sensor name |
boolean OpenHRP::ImpedanceControllerService::startImpedanceControllerNoWait | ( | in string | name | ) |
start impedance controller without waiting for transition.
name | impedance controller param's name, which basically corresponds to force sensor name |
boolean OpenHRP::ImpedanceControllerService::stopImpedanceController | ( | in string | name | ) |
stop impedance controller with waiting for transition.
name | impedance controller param's name, which basically corresponds to force sensor name |
boolean OpenHRP::ImpedanceControllerService::stopImpedanceControllerNoWait | ( | in string | name | ) |
stop impedance controller without waiting for transition.
name | impedance controller param's name, which basically corresponds to force sensor name |
void OpenHRP::ImpedanceControllerService::waitImpedanceControllerTransition | ( | in string | name | ) |
wait for impedance controller mode transition.
name | impedance controller param's name, which basically corresponds to force sensor name |