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

import"ObjectContactTurnaroundDetectorService.idl";

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, TOTAL_MOMENT2 }
 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. More...
 
DetectorMode checkObjectContactTurnaroundDetection ()
 Check ObjectContactTurnaroundDetector. More...
 
boolean setObjectContactTurnaroundDetectorParam (in objectContactTurnaroundDetectorParam i_param)
 set object contact turnaround detector parameters. More...
 
boolean getObjectContactTurnaroundDetectorParam (out objectContactTurnaroundDetectorParam i_param)
 get object contact turnaround detector parameters. More...
 
boolean getObjectForcesMoments (out Dbl3Sequence o_forces, out Dbl3Sequence o_moments, out DblSequence3 o_3dofwrench, out double o_fric_coeff_wrench)
 get Current force and moment for object More...
 

Member Typedef Documentation

◆ Dbl3Sequence

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

◆ DblArray3

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

◆ DblSequence3

◆ StrSequence

Member Enumeration Documentation

◆ DetectorMode

Mode of object contact turnaround detector.

Enumerator
MODE_DETECTOR_IDLE 
MODE_STARTED 
MODE_DETECTED 
MODE_MAX_TIME 

◆ DetectorTotalWrench

Flag for whether total force or total moment is checked.

Enumerator
TOTAL_FORCE 

Check resultant force.

TOTAL_MOMENT 

Check resultant moment using force measurements.

TOTAL_MOMENT2 

Check resultant moment using force and moment measurements.

Member Function Documentation

◆ checkObjectContactTurnaroundDetection()

DetectorMode OpenHRP::ObjectContactTurnaroundDetectorService::checkObjectContactTurnaroundDetection ( )

Check ObjectContactTurnaroundDetector.

◆ getObjectContactTurnaroundDetectorParam()

boolean OpenHRP::ObjectContactTurnaroundDetectorService::getObjectContactTurnaroundDetectorParam ( out objectContactTurnaroundDetectorParam  i_param)

get object contact turnaround detector parameters.

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

◆ getObjectForcesMoments()

boolean OpenHRP::ObjectContactTurnaroundDetectorService::getObjectForcesMoments ( out Dbl3Sequence  o_forces,
out Dbl3Sequence  o_moments,
out DblSequence3  o_3dofwrench,
out double  o_fric_coeff_wrench 
)

get Current force and moment for object

Parameters
o_forcesand o_moments are list of forces[N] and moments[Nm] at end-effectors. o_3dofwrench is resultant force[N] or wrench[Nm]. o_fric_coeff_wrench is firction coefficient wrench[N or Nm].
Returns
true if set successfully, false otherwise

◆ setObjectContactTurnaroundDetectorParam()

boolean OpenHRP::ObjectContactTurnaroundDetectorService::setObjectContactTurnaroundDetectorParam ( in objectContactTurnaroundDetectorParam  i_param)

set object contact turnaround detector parameters.

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

◆ startObjectContactTurnaroundDetection()

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: