Basic RT components and utilities  315.10.1
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...
 
struct  objectTurnaroundDetectorParam
 ObjectTurnaroundDetectorParam parameters. More...
 

Public Types

enum  ControllerMode { MODE_IDLE, MODE_IMP }
 Mode of controller. More...
 
enum  DetectorMode { MODE_DETECTOR_IDLE, MODE_STARTED, MODE_DETECTED, MODE_MAX_TIME }
 Mode of object turnaround detector. More...
 
enum  DetectorTotalWrench { TOTAL_FORCE, TOTAL_MOMENT }
 Flag for whether total force or total moment is checked. 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...
 
void startObjectTurnaroundDetection (in double i_ref_diff_wrench, in double i_max_time, in StrSequence i_ee_names)
 Start ObjectTurnaroundDetector. More...
 
DetectorMode checkObjectTurnaroundDetection ()
 Check ObjectTurnaroundDetector. More...
 
boolean setObjectTurnaroundDetectorParam (in objectTurnaroundDetectorParam i_param)
 set object turnaround detector parameters. More...
 
boolean getObjectTurnaroundDetectorParam (out objectTurnaroundDetectorParam i_param)
 get object turnaround detector parameters. More...
 
boolean getObjectForcesMoments (out Dbl3Sequence o_forces, out Dbl3Sequence o_moments, out DblSequence3 o_3dofwrench)
 get Current force and moment for object More...
 

Member Typedef Documentation

typedef sequence<sequence<double, 3> > OpenHRP::ImpedanceControllerService::Dbl3Sequence
typedef double OpenHRP::ImpedanceControllerService::DblArray3[3]

Member Enumeration Documentation

Mode of controller.

Enumerator
MODE_IDLE 
MODE_IMP 

Mode of object turnaround detector.

Enumerator
MODE_DETECTOR_IDLE 
MODE_STARTED 
MODE_DETECTED 
MODE_MAX_TIME 

Flag for whether total force or total moment is checked.

Enumerator
TOTAL_FORCE 
TOTAL_MOMENT 

Member Function Documentation

DetectorMode OpenHRP::ImpedanceControllerService::checkObjectTurnaroundDetection ( )

Check ObjectTurnaroundDetector.

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
boolean OpenHRP::ImpedanceControllerService::getObjectForcesMoments ( out Dbl3Sequence  o_forces,
out Dbl3Sequence  o_moments,
out DblSequence3  o_3dofwrench 
)

get Current force and moment for object

Parameters
i_paramoutput force and moment
Returns
true if set successfully, false otherwise
boolean OpenHRP::ImpedanceControllerService::getObjectTurnaroundDetectorParam ( out objectTurnaroundDetectorParam  i_param)

get object turnaround detector parameters.

Parameters
i_paraminput new parameters
Returns
true if set successfully, false otherwise
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
boolean OpenHRP::ImpedanceControllerService::setObjectTurnaroundDetectorParam ( in objectTurnaroundDetectorParam  i_param)

set object turnaround detector parameters.

Parameters
i_paraminput new parameters
Returns
true if set successfully, false otherwise
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
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
void OpenHRP::ImpedanceControllerService::startObjectTurnaroundDetection ( in double  i_ref_diff_wrench,
in double  i_max_time,
in StrSequence  i_ee_names 
)

Start ObjectTurnaroundDetector.

Parameters
ref_diff_wrenchis force or moment value.
max_timeis max time [s].
i_ee_namesis list of end effector
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
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
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: