CollisionCheck¶
Introduction¶
The CollisionCheck module is an optional on-board module of the rc_visard and is licensed with any of the modules ItemPick and BoxPick or SilhouetteMatch. Otherwise it requires a separate CollisionCheck license to be purchased.
The module provides an easy way to check if a gripper is in collision with a load carrier, or other detected objects (only in combination with SilhouetteMatch). It is integrated with the ItemPick and BoxPick and SilhouetteMatch modules, but can be used as standalone product. The models of the grippers for collision checking have to be defined in the GripperDB module.
Warning
Collisions are checked only between the load carrier and the gripper, not the robot itself, the flange, other objects or
the item located in the robot gripper. Only in combination with SilhouetteMatch,
and only in case the selected template contains a collision
geometry and check_collisions_with_matches
is enabled in the respective detection module,
also collisions between the gripper and other detected objects are checked.
Collisions with objects that cannot be detected will not be checked.
Collision checking with | detected load carrier, detected objects (only SilhouetteMatch), baseplane (only SilhouetteMatch) |
Collision checking available in | ItemPick and BoxPick, SilhouetteMatch |
Collision checking¶
Stand-alone collision checking¶
The check_collisions
service call triggers collision checking between the chosen gripper and the provided load carriers
for each of the provided grasps. Checking collisions with other objects
is not possible with the stand-alone check_collisions
service.
The CollisionCheck module checks if the chosen gripper is
in collision with at least one of the load carriers, when the TCP of the gripper is positioned in the
grasp position. It is possible to check the collision with multiple load carriers simultaneously. The grasps
which are in collision with any of the defined load carriers will be returned as colliding.
The pre_grasp_offset
can be used for additional collision checking.
The pre-grasp offset \(P_{off}\) is the offset between the grasp point \(P_{grasp}\) and the pre-grasp position \(P_{pre}\)
in the grasp’s coordinate frame (see Fig. 48).
If the pre-grasp offset is defined, the grasp will be detected as colliding
if the gripper is in collision at any point
during motion from the pre-grasp position to the grasp position (assuming
a linear movement).
Collision checking within other modules¶
Collision checking is integrated in the following modules’ services:
- ItemPick and BoxPick:
compute_grasps
(see compute_grasps for ItemPick and compute_grasps for BoxPick) - SilhouetteMatch:
detect_object
(see detect_object)
Each of these services can take a collision_detection
argument consisting of the gripper_id
of the gripper
and optionally the pre_grasp_offset
as described in the previous section
Stand-alone collision checking.
When the collision_detection
argument is given, these services only return the
grasps at which the gripper is not in collision with the load carrier detected by these services. For this,
a load carrier ID has to be provided to these services as well.
Only for SilhouetteMatch, and only in case the selected template contains a collision
geometry and check_collisions_with_matches
is enabled in the respective detection module,
grasp points at which the gripper would be in collision with other detected objects are also rejected. The object
on which the grasp point to be checked is located, is excluded from the collision check.
In SilhouetteMatch, collisions between
the gripper and the base plane can be checked, if check_collisions_with_base_plane
is enabled in SilhouetteMatch.
Warning
Collisions are checked only between the load carrier and the gripper, not the robot itself, the flange, other objects or
the item located in the robot gripper. Only in combination with SilhouetteMatch,
and only in case the selected template contains a collision
geometry and check_collisions_with_matches
is enabled in the respective detection module,
also collisions between the gripper and other detected objects are checked.
Collisions with objects that cannot be detected will not be checked.
The collision-check results are affected by run-time parameters, which are listed and explained further below.
Parameters¶
The CollisionCheck module is called rc_collision_check
in the REST-API and is represented in the
Web GUI
under .
The user can explore and configure the rc_collision_check
module’s run-time parameters, e.g. for development and testing, using the Web GUI or the
REST-API interface.
Parameter overview¶
This module offers the following run-time parameters:
Name | Type | Min | Max | Default | Description |
---|---|---|---|---|---|
check_bottom |
bool | false | true | true | Whether to enable collision checking with the bottom of the load carrier |
check_flange |
bool | false | true | true | Whether all grasps with the flange inside the load carrier should be marked as colliding |
collision_dist |
float64 | 0.0 | 0.1 | 0.01 | Minimum distance in meters between any element of the gripper and the load carrier or the base plane (only SilhouetteMatch) for a collision-free grasp |
Description of run-time parameters¶
Each run-time parameter is represented by a row in the Web GUI’s Settings section under
. The name in the Web GUI is given in brackets behind the parameter name:collision_dist
(Collision Distance)¶
Minimal distance in meters between any part of the gripper and the load carrier and/or the base plane (only SilhouetteMatch) for a grasp to be considered collision free.
Warning
The collision distance is not applied when checking collisions between the gripper and other detected objects. It is not applied when checking if the flange is inside the load carrier (
check_flange
), either.Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_collision_check/parameters?collision_dist=<value>
PUT http://<host>/api/v1/nodes/rc_collision_check/parameters?collision_dist=<value>
check_flange
(Check Flange)¶
Performs an additional safety check as described in Robot flange radius. If this parameter is set, all grasps in which any part of the robot’s flange is inside the load carrier are marked as colliding.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_collision_check/parameters?check_flange=<value>
PUT http://<host>/api/v1/nodes/rc_collision_check/parameters?check_flange=<value>
check_bottom
(Check Bottom)¶
When this check is enabled the collisions will be checked not only with the side walls of the load carrier but also with its bottom. It might be necessary to disable this check if the TCP is inside the collision geometry (e.g. is defined inside a suction cup).
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_collision_check/parameters?check_bottom=<value>
PUT http://<host>/api/v1/nodes/rc_collision_check/parameters?check_bottom=<value>
Status values¶
The rc_collision_check
module reports the following status values:
Name | Description |
---|---|
last_evaluated_grasps |
Number of evaluated grasps |
last_collision_free_grasps |
Number of collision-free grasps |
collision_check_time |
Collision checking runtime |
Services¶
The user can explore and call the rc_collision_check
module’s services,
e.g. for development and testing, using
REST-API interface or
the rc_visard
Web GUI.
The CollisionCheck module offers the following services.
check_collisions
¶
Triggers a collision check between a gripper and a load carrier.
Details
This service can be called as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_collision_check/services/check_collisionsPUT http://<host>/api/v1/nodes/rc_collision_check/services/check_collisionsRequired arguments:
grasps
: list of grasps that should be checked.
load_carriers
: list of load carriers against which the collision should be checked. The fields of the load carrier definition are described in Detection of load carriers. The position frame of the grasps and load carriers has to be the same.
gripper_id
: the id of the gripper that is used to check the collisions. The gripper has to be configured beforehand.Optional arguments:
pre_grasp_offset
: the offset in meters from the grasp position to the pre-grasp position in the grasp frame. If this argument is set, the collisions will not only be checked in the grasp point, but also on the path from the pre-grasp position to the grasp position (assuming a linear movement).The definition for the request arguments with corresponding datatypes is:
{ "args": { "grasps": [ { "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "uuid": "string" } ], "gripper_id": "string", "load_carriers": [ { "id": "string", "inner_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "outer_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "rim_thickness": { "x": "float64", "y": "float64" } } ], "pre_grasp_offset": { "x": "float64", "y": "float64", "z": "float64" } } }
colliding_grasps
: list of grasps in collision with one or more load carriers.
collision_free_grasps
: list of collision-free grasps.
return_code
: holds possible warnings or error codes and messages.The definition for the response with corresponding datatypes is:
{ "name": "check_collisions", "response": { "colliding_grasps": [ { "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "uuid": "string" } ], "collision_free_grasps": [ { "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "uuid": "string" } ], "return_code": { "message": "string", "value": "int16" } } }
reset_defaults
¶
Resets all parameters of the module to its default values, as listed in above table.
Details
This service can be called as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_collision_check/services/reset_defaultsPUT http://<host>/api/v1/nodes/rc_collision_check/services/reset_defaultsThis service has no arguments.The definition for the response with corresponding datatypes is:
{ "name": "reset_defaults", "response": { "return_code": { "message": "string", "value": "int16" } } }
set_gripper
(deprecated)¶
Persistently stores a gripper on the rc_visard.
This service is not available in API version 2. Use set_gripper inrc_gripper_db
instead.This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_collision_check/services/set_gripperThe definitions of the request and response are the same as described in set_gripper in
rc_gripper_db
.
get_grippers
(deprecated)¶
Returns the configured grippers with the requested
gripper_ids
.This service is not available in API version 2. Use get_grippers inrc_gripper_db
instead.This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_collision_check/services/get_grippersThe definitions of the request and response are the same as described in get_grippers in
rc_gripper_db
.
delete_grippers
(deprecated)¶
Deletes the configured grippers with the requested
gripper_ids
.This service is not available in API version 2. Use delete_grippers inrc_gripper_db
instead.This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_collision_check/services/delete_grippersThe definitions of the request and response are the same as described in delete_grippers in
rc_gripper_db
.
Return codes¶
Each service response contains a return_code
,
which consists of a value
plus an optional message
.
A successful service returns with a return_code
value of 0
.
Negative return_code
values indicate that the service failed.
Positive return_code
values indicate that the service succeeded with additional information.
The smaller value is selected in case a service has multiple return_code
values,
but all messages are appended in the return_code
message.
The following table contains a list of common codes:
Code | Description |
---|---|
0 | Success |
-1 | An invalid argument was provided |
-7 | Data could not be read or written to persistent storage |
-9 | No valid license for the module |
-10 | New gripper could not be added as the maximum storage capacity of grippers has been exceeded |
10 | The maximum storage capacity of grippers has been reached |
11 | Existing gripper was overwritten |