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
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:
-
Member Function Documentation
Check ObjectContactTurnaroundDetector.
get object contact turnaround detector parameters.
- Parameters:
-
i_param | input new parameters |
- Returns:
- true if set successfully, false otherwise
get Current force and moment for object
- Parameters:
-
i_param | output force and moment |
- Returns:
- true if set successfully, false otherwise
set object contact turnaround detector parameters.
- Parameters:
-
i_param | input new parameters |
- Returns:
- true if set successfully, false otherwise
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: