import"ObjectContactTurnaroundDetectorService.idl";
◆ Dbl3Sequence
◆ DblArray3
typedef double OpenHRP::ObjectContactTurnaroundDetectorService::DblArray3[3] |
◆ DblSequence3
◆ StrSequence
◆ 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.
|
◆ checkObjectContactTurnaroundDetection()
DetectorMode OpenHRP::ObjectContactTurnaroundDetectorService::checkObjectContactTurnaroundDetection |
( |
| ) |
|
Check ObjectContactTurnaroundDetector.
◆ getObjectContactTurnaroundDetectorParam()
get object contact turnaround detector parameters.
- Parameters
-
i_param | input 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_forces | and 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()
set object contact turnaround detector parameters.
- Parameters
-
i_param | input 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_wrench | is force or moment value. |
max_time | is max time [s]. |
i_ee_names | is list of end effector |
The documentation for this interface was generated from the following file: