Basic RT components and utilities  315.12.1
Classes | Public Types | Public Member Functions
OpenHRP::ObjectContactTurnaroundDetectorService Interface Reference

import "ObjectContactTurnaroundDetectorService.idl";

List of all members.

Classes

struct  objectContactTurnaroundDetectorParam
 ObjectContactTurnaroundDetectorParam parameters. More...

Public Types

enum  DetectorMode { MODE_DETECTOR_IDLE, MODE_STARTED, MODE_DETECTED, MODE_MAX_TIME }
 Mode of object contact 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< string > StrSequence
typedef sequence< sequence
< double, 3 > > 
Dbl3Sequence

Public Member Functions

void startObjectContactTurnaroundDetection (in double i_ref_diff_wrench, in double i_max_time, in StrSequence i_ee_names)
 Start ObjectContactTurnaroundDetector.
DetectorMode checkObjectContactTurnaroundDetection ()
 Check ObjectContactTurnaroundDetector.
boolean setObjectContactTurnaroundDetectorParam (in objectContactTurnaroundDetectorParam i_param)
 set object contact turnaround detector parameters.
boolean getObjectContactTurnaroundDetectorParam (out objectContactTurnaroundDetectorParam i_param)
 get object contact turnaround detector parameters.
boolean getObjectForcesMoments (out Dbl3Sequence o_forces, out Dbl3Sequence o_moments, out DblSequence3 o_3dofwrench)
 get Current force and moment for object

Member Typedef Documentation

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

Member Enumeration Documentation

Mode of object contact 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

Check ObjectContactTurnaroundDetector.

get object contact turnaround detector parameters.

Parameters:
i_paraminput new parameters
Returns:
true if set successfully, false otherwise

get Current force and moment for object

Parameters:
i_paramoutput force and moment
Returns:
true if set successfully, false otherwise

set object contact turnaround detector parameters.

Parameters:
i_paraminput new parameters
Returns:
true if set successfully, false otherwise
void OpenHRP::ObjectContactTurnaroundDetectorService::startObjectContactTurnaroundDetection ( in double  i_ref_diff_wrench,
in double  i_max_time,
in StrSequence  i_ee_names 
)

Start ObjectContactTurnaroundDetector.

Parameters:
ref_diff_wrenchis force or moment value.
max_timeis max time [s].
i_ee_namesis list of end effector

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