Basic RT components and utilities  315.15.0
Classes | Public Types | Public Member Functions | List of all members
OpenHRP::ImpedanceControllerService Interface Reference

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. More...
 
boolean startImpedanceControllerNoWait (in string name)
 start impedance controller without waiting for transition. More...
 
boolean stopImpedanceController (in string name)
 stop impedance controller with waiting for transition. More...
 
boolean stopImpedanceControllerNoWait (in string name)
 stop impedance controller without waiting for transition. More...
 
boolean setImpedanceControllerParam (in string name, in impedanceParam i_param)
 set impedance parameters. More...
 
boolean getImpedanceControllerParam (in string name, out impedanceParam i_param)
 get impedance parameters. More...
 
void waitImpedanceControllerTransition (in string name)
 wait for impedance controller mode transition. More...
 

Member Typedef Documentation

◆ Dbl3Sequence

typedef sequence<sequence<double, 3> > OpenHRP::ImpedanceControllerService::Dbl3Sequence

◆ DblArray3

typedef double OpenHRP::ImpedanceControllerService::DblArray3[3]

◆ DblSequence

◆ DblSequence3

◆ StrSequence

Member Enumeration Documentation

◆ ControllerMode

Mode of controller.

Enumerator
MODE_IDLE 
MODE_IMP 

Member Function Documentation

◆ getImpedanceControllerParam()

boolean OpenHRP::ImpedanceControllerService::getImpedanceControllerParam ( in string  name,
out impedanceParam  i_param 
)

get impedance parameters.

Parameters
i_paramouput impedance parameters
nameimpedance 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_paraminput new impedance parameters
nameimpedance 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
nameimpedance 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
nameimpedance 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
nameimpedance 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
nameimpedance 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
nameimpedance controller param's name, which basically corresponds to force sensor name

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