import"ImpedanceControllerService.idl";
◆ Dbl3Sequence
◆ DblArray3
typedef double OpenHRP::ImpedanceControllerService::DblArray3[3] |
◆ DblSequence
◆ DblSequence3
◆ StrSequence
◆ ControllerMode
Mode of controller.
Enumerator |
---|
MODE_IDLE | |
MODE_IMP | |
◆ getImpedanceControllerParam()
boolean OpenHRP::ImpedanceControllerService::getImpedanceControllerParam |
( |
in string |
name, |
|
|
out impedanceParam |
i_param |
|
) |
| |
get impedance parameters.
- Parameters
-
i_param | ouput impedance parameters |
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ setImpedanceControllerParam()
boolean OpenHRP::ImpedanceControllerService::setImpedanceControllerParam |
( |
in string |
name, |
|
|
in impedanceParam |
i_param |
|
) |
| |
set impedance parameters.
- Parameters
-
i_param | input new impedance parameters |
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ startImpedanceController()
boolean OpenHRP::ImpedanceControllerService::startImpedanceController |
( |
in string |
name | ) |
|
start impedance controller with waiting for transition.
- Parameters
-
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ startImpedanceControllerNoWait()
boolean OpenHRP::ImpedanceControllerService::startImpedanceControllerNoWait |
( |
in string |
name | ) |
|
start impedance controller without waiting for transition.
- Parameters
-
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ stopImpedanceController()
boolean OpenHRP::ImpedanceControllerService::stopImpedanceController |
( |
in string |
name | ) |
|
stop impedance controller with waiting for transition.
- Parameters
-
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ stopImpedanceControllerNoWait()
boolean OpenHRP::ImpedanceControllerService::stopImpedanceControllerNoWait |
( |
in string |
name | ) |
|
stop impedance controller without waiting for transition.
- Parameters
-
name | impedance controller param's name, which basically corresponds to force sensor name |
- Returns
- true if set successfully, false otherwise
◆ waitImpedanceControllerTransition()
void OpenHRP::ImpedanceControllerService::waitImpedanceControllerTransition |
( |
in string |
name | ) |
|
wait for impedance controller mode transition.
- Parameters
-
name | impedance controller param's name, which basically corresponds to force sensor name |
The documentation for this interface was generated from the following file: