ItemPick and BoxPick¶
Introduction¶
The ItemPick and BoxPick components are optional on-board components of the rc_visard.
Note
The components are optional and require separate ItemPick or BoxPick licenses to be purchased.
The components provide out-of-the-box perception solutions for robotic pick-and-place applications. ItemPick targets the detection of flat surfaces of unknown objects for picking with a suction gripper. BoxPick detects rectangular surfaces and determines their position, orientation and size for grasping. The interface of both components is very similar. Therefore both components are described together in this chapter.
In addition, both components offer:
- A dedicated page on the rc_visard Web GUI for easy setup, configuration, testing, and application tuning.
- The definition of regions of interest to select relevant volumes in the scene (see Region of interest functionality).
- A load carrier detection functionality for bin-picking applications (see Load carrier functionality), to provide grasps for items inside a bin only.
- The definition of compartments inside a load carrier to provide grasps for specific volumes of the bin only.
- Support for static and robot-mounted cameras and optional integration with the Hand-eye calibration component, to provide grasps in the user-configured external reference frame.
- A quality value associated to each suggested grasp and related to the flatness of the grasping surface.
- Sorting of grasps according to gravity and size so that items on top of a pile are grasped first.
Note
In this chapter, cluster and surface are used as synonyms and identify a set of points (or pixels) with defined geometrical properties.
Detection of items (BoxPick)¶
The BoxPick component supports the detection of multiple item_models
of
type
RECTANGLE
.
Each item model is defined by its minimum and maximum size, with the
minimum dimensions strictly smaller than the maximum dimensions.
The dimensions should be given fairly accurately to avoid misdetections,
while still considering a certain tolerance to account for possible production variations
and measurement inaccuracies.
Optionally, further information can be given to the BoxPick component:
- The ID of the load carrier which contains the items to be detected.
- A compartment inside the load carrier where to detect items.
- The ID of the region of interest where to search for the load carriers if a load carrier is set. Otherwise, the ID of the region of interest where to search for the items.
- The current robot pose in case the camera is mounted on the robot and
the chosen coordinate frame for the poses is
external
or the chosen region of interest is defined in the external frame.
The detected item
poses are given relative to the centers of the rectangles,
with the z axis pointing towards the camera.
Each detected item includes a uuid
(Universally Unique Identifier) and the
timestamp
of the oldest image that was used to detect it.
Computation of grasps¶
The ItemPick and BoxPick components offer a service for computing grasps for suction grippers. The gripper is defined by its suction surface length and width.
The ItemPick component identifies flat surfaces in the scene and supports
flexible and/or deformable items. The type
of these item_models
is
called UNKNOWN
since they don’t need to have a standard geometrical shape.
Optionally, the user can also specify the minimum and maximum size of the item.
For BoxPick, the grasps are computed on the detected rectangular items
(see Detection of items (BoxPick)).
Optionally, further information can be given to the components in a grasp computation request:
- The ID of the load carrier which contains the items to be grasped.
- A compartment inside the load carrier where to compute grasps.
The
load_carrier_compartment
is a box whosepose
is defined with respect to the load carrier reference frame.
- The ID of the region of interest where to search for the load carriers if a load carrier is set. Otherwise, the ID of the region of interest where to compute grasps.
- Collision detection information: The ID of the gripper to enable collision checking and optionally a pre-grasp offset to define a pre-grasp position. Details on collision checking are given below in CollisionCheck.
A grasp provided by the ItemPick and BoxPick components represents the recommended
pose of the TCP (Tool Center Point) of the suction gripper.
The grasp type
is always set to SUCTION
.
The computed grasp pose is the center of the biggest ellipse that can be inscribed in
each surface.
The grasp orientation is a right-handed coordinate system and is defined such
that its z axis is normal to the surface pointing inside the object at the grasp position and
its x axis is directed along the maximum elongation of the ellipse.
Each grasp includes the dimensions of the maximum suction surface available,
modelled as an ellipse of axes max_suction_surface_length
and
max_suction_surface_width
. The user is enabled to filter grasps by specifying
the minimum suction surface required by the suction device in use.
In the BoxPick component, the grasp position corresponds to the center of the detected rectangle and the dimensions of the maximum suction surface available matches the estimated rectangle dimensions. Detected rectangles with missing data or occlusions by other objects for more than 15% of their surface do not get an associated grasp.
Each grasp also includes a quality
value, which gives an
indication of the flatness of the grasping surface.
The quality
value varies between 0 and 1, where higher numbers correspond to a
flatter reconstructed surface.
The grasp definition is complemented by a uuid
(Universally Unique Identifier)
and the timestamp
of the oldest image that was used to compute the grasp.
Interaction with other components¶
Internally, the ItemPick and BoxPick components depend on, and interact with other on-board components as listed below.
Note
All changes and configuration updates to these components will affect the performance of the ItemPick and BoxPick components.
Stereo camera and Stereo matching¶
The ItemPick and BoxPick components make internally use of the following data:
- Rectified images from the Stereo camera component
(
rc_stereocamera
); - Disparity, error, and confidence images from the Stereo matching component
(
rc_stereomatching
).
All processed images are guaranteed to be captured after the component trigger time.
Estimation of gravity vector¶
For each load carrier detection and grasp computation, the components estimate the gravity vector by subscribing to the rc_visard’s IMU data stream.
Note
The gravity vector is estimated from linear acceleration readings from the on-board IMU. For this reason, the ItemPick and BoxPick components require the rc_visard to remain still while the gravity vector is being estimated.
IO and Projector Control¶
In case the rc_visard is used in conjunction with an external random dot projector and
the IO and Projector Control component (rc_iocontrol
),
it is recommended to connect the projector to GPIO Out 1 and set
the stereo-camera component’s acquisition mode to SingleFrameOut1
(see Stereo matching parameters), so that
on each image acquisition trigger an image with and without projector pattern is acquired.
Alternatively, the output mode for the GPIO output in use should be set to ExposureAlternateActive
(see Description of run-time parameters).
In either case,
the Auto Exposure Mode exp_auto_mode
should be set to AdaptiveOut1
to optimize the exposure
of both images (see Stereo camera parameters).
Hand-eye calibration¶
In case the camera has been calibrated to a robot, the ItemPick and BoxPick components
can automatically provide poses in the robot coordinate frame.
For the ItemPick and BoxPick nodes’ Services, the frame of the
output poses can be controlled with the pose_frame
argument.
Two different pose_frame
values can be chosen:
- Camera frame (
camera
). All poses provided by the components are in the camera frame, and no prior knowledge about the pose of the camera in the environment is required. This means that the configured regions of interest and load carriers move with the camera. It is the user’s responsibility to update the configured poses if the camera frame moves (e.g. with a robot-mounted camera). - External frame (
external
). All poses provided by the components are in the external frame, configured by the user during the hand-eye calibration process. The component relies on the on-board Hand-eye calibration component to retrieve the sensor mounting (static or robot mounted) and the hand-eye transformation. If the mounting is static, no further information is needed. If the sensor is robot-mounted, therobot_pose
is required to transform poses to and from theexternal
frame.
Note
If no hand-eye calibration is available, all pose_frame
values should be set to camera
.
All pose_frame
values that are not camera
or external
are rejected.
CollisionCheck¶
Collision checking can be easily enabled for
grasp computation of the ItemPick and BoxPick components by passing the ID of the used gripper and
optionally a pre-grasp offset to the
compute_grasps
service call. The gripper has to be
defined in the CollisionCheck component
(see Setting a gripper)
and details about collision checking are given in Collision checking within other modules.
If collision checking is enabled, only grasps which are collision free will be returned. However, the visualization images on the ItemPick or BoxPick tab of the Web GUI also show colliding grasp points as black ellipses.
The CollisionCheck module’s run-time parameters affect the collision detection as described in CollisionCheck Parameters.
Parameters¶
The ItemPick and BoxPick components are called rc_itempick
and rc_boxpick
in the REST-API and are represented by the ItemPick and BoxPick pages in the Modules tab of the
Web GUI.
The user can explore and configure the rc_itempick
and rc_boxpick
component’s run-time parameters, e.g. for development and testing, using the Web GUI or the
REST-API interface.
Parameter overview¶
This component offers the following run-time parameters:
Name | Type | Min | Max | Default | Description |
---|---|---|---|---|---|
max_grasps |
int32 | 1 | 20 | 5 | Maximum number of provided grasps |
prefer_splits |
bool | false | true | false | Only for rc_boxpick. Indicates whether rectangles are split into smaller ones when possible |
Name | Type | Min | Max | Default | Description |
---|---|---|---|---|---|
load_carrier_crop_distance |
float64 | 0.0 | 0.05 | 0.005 | Safety margin in meters by which the load carrier inner dimensions are reduced to define the region of interest for detection |
load_carrier_model_tolerance |
float64 | 0.003 | 0.025 | 0.008 | Indicates how much the estimated load carrier dimensions are allowed to differ from the load carrier model dimensions in meters |
Name | Type | Min | Max | Default | Description |
---|---|---|---|---|---|
cluster_max_dimension |
float64 | 0.05 | 0.8 | 0.3 | Only for rc_itempick. Diameter of the largest sphere enclosing each cluster in meters. Clusters larger than this value are filtered out before grasp computation. |
cluster_max_curvature |
float64 | 0.005 | 0.5 | 0.11 | Maximum curvature allowed within one cluster. The smaller this value, the more clusters will be split apart. |
clustering_patch_size |
int32 | 3 | 10 | 4 | Only for rc_itempick. Size in pixels of the square patches the depth map is subdivided into during the first clustering step |
clustering_max_surface_rmse |
float64 | 0.0005 | 0.01 | 0.004 | Maximum root-mean-square error (RMSE) in meters of points belonging to a surface |
clustering_discontinuity_factor |
float64 | 0.5 | 5.0 | 1.0 | Factor used to discriminate depth discontinuities within a patch. The smaller this value, the more clusters will be split apart. |
Description of run-time parameters¶
Each run-time parameter is represented by a row on the Web GUI’s ItemPick or BoxPick page in the Modules tab. The name in the Web GUI is given in brackets behind the parameter name and the parameters are listed in the order they appear in the Web GUI:
max_grasps
(Maximum Grasps)¶
sets the maximum number of provided grasps.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?max_grasps=<value>
prefer_splits
(Only for BoxPick, Prefer Splits)¶
determines whether rectangles should be split into smaller ones if the smaller ones also match the given item models. This parameter should be set to for packed box layouts in which the given item models would also match a rectangle of the size of two adjoining boxes. If this parameter is set to false, the larger rectangles will be preferred in these cases.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/rc_boxpick/parameters?prefer_splits=<value>
load_carrier_model_tolerance
(Model Tolerance)¶
see Parameters of the load carrier functionality.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?load_carrier_model_tolerance=<value>
load_carrier_crop_distance
(Crop Distance)¶
see Parameters of the load carrier functionality.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?load_carrier_crop_distance=<value>
cluster_max_dimension
(Only for ItemPick, Cluster Maximum Dimension)¶
sets the diameter of the largest circle enclosing each cluster in meters. Clusters larger than this value are filtered out before grasp computation.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/rc_itempick/parameters?cluster_max_dimension=<value>
cluster_max_curvature
(Cluster Maximum Curvature)¶
is the maximum curvature allowed within one cluster. The smaller this value, the more clusters will be split apart.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?cluster_max_curvature=<value>
clustering_patch_size
(Only for ItemPick, Patch Size)¶
is the size of the square patches the depth map is subdivided into during the first clustering step in pixels.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/rc_itempick/parameters?clustering_patch_size=<value>
clustering_discontinuity_factor
(Discontinuity Factor)¶
is the factor used to discriminate depth discontinuities within a patch. The smaller this value, the more clusters will be split apart.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?clustering_discontinuity_factor=<value>
clustering_max_surface_rmse
(Maximum Surface RMSE)¶
is the maximum root-mean-square error (RMSE) in meters of points belonging to a surface.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/parameters?clustering_max_surface_rmse=<value>
Status values¶
The rc_itempick
and rc_boxpick
components report the following status values:
Name | Description |
---|---|
data_acquisition_time |
Time in seconds required by the last active service to acquire images. Standard values are between 0.5 s and 0.6 s with High depth image quality. |
grasp_computation_time |
Processing time of the last grasp computation in seconds |
last_timestamp_processed |
The timestamp of the last processed dataset |
load_carrier_detection_time |
Processing time of the last load carrier detection in seconds |
state |
The current state of the rc_itempick and rc_boxpick node |
The reported state
can take one of the following values.
State name | Description |
---|---|
IDLE | The component is idle. |
RUNNING | The component is running and ready for load carrier detection and grasp computation. |
FATAL | A fatal error has occurred. |
Services¶
The user can explore and call the rc_itempick
and rc_boxpick
component’s services,
e.g. for development and testing, using the
REST-API interface or
the rc_visard
Web GUI.
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 |
-4 | Data acquisition took longer than the maximum allowed time of 5.0 seconds |
-10 | New element could not be added as the maximum storage capacity of load carriers or regions of interest has been exceeded |
-200 | Fatal internal error |
-301 | More than one item model of type UNKNOWN provided to the compute_grasps service |
-302 | More than one load carrier provided to the detect_load_carriers or detect_filling_level services, but only one is supported |
10 | The maximum storage capacity of load carriers or regions of interest has been reached |
11 | An existent persistent model was overwritten by the call to set_load_carrier or set_region_of_interest |
100 | The requested load carriers were not detected in the scene |
101 | No valid surfaces or grasps were found in the scene |
102 | The detected load carrier is empty |
103 | All computed grasps are in collision with the load carrier |
200 | The component is in state IDLE |
300 | A valid robot_pose was provided as argument but it is not required |
400 | No item_models were provided to the compute_grasps service request |
The ItemPick and BoxPick components offer the following services.
start
¶
Starts the component. If the command is accepted, the component moves to state
RUNNING
. Thecurrent_state
value in the service response may differ fromRUNNING
if the state transition is still in process when the service returns.This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/start
This service has no arguments.
The definition for the response with corresponding datatypes is:
{ "name": "start", "response": { "accepted": "bool", "current_state": "string" } }
stop
¶
Stops the component. If the command is accepted, the component moves to state
IDLE
. Thecurrent_state
value in the service response may differ fromIDLE
if the state transition is still in process when the service returns.This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/stop
This service has no arguments.
The definition for the response with corresponding datatypes is:
{ "name": "stop", "response": { "accepted": "bool", "current_state": "string" } }
set_region_of_interest
¶
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/set_region_of_interest
get_regions_of_interest
¶
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/get_regions_of_interest
delete_regions_of_interest
¶
see delete_regions_of_interest.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/delete_regions_of_interest
set_load_carrier
¶
see set_load_carrier.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/set_load_carrier
get_load_carriers
¶
see get_load_carriers.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/get_load_carriers
delete_load_carriers
¶
see delete_load_carriers.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/delete_load_carriers
detect_load_carriers
¶
see detect_load_carriers.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/detect_load_carriers
detect_filling_level
¶
see detect_filling_level.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/detect_filling_level
detect_items
(BoxPick only)¶
Triggers the detection of rectangles as described in Detection of items (BoxPick).
This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_boxpick/services/detect_itemsRequest:
The definition for the request arguments with corresponding datatypes is:
{ "args": { "item_models": [ { "rectangle": { "max_dimensions": { "x": "float64", "y": "float64" }, "min_dimensions": { "x": "float64", "y": "float64" } }, "type": "string" } ], "load_carrier_compartment": { "box": { "x": "float64", "y": "float64", "z": "float64" }, "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } } }, "load_carrier_id": "string", "pose_frame": "string", "region_of_interest_id": "string", "robot_pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } } } }Required arguments:
pose_frame
: see Hand-eye calibration.
item_models
: list of rectangles with minimum and maximum size, with the minimum dimensions strictly smaller than the maximum dimensions. The dimensions should be given fairly accurately to avoid misdetections, while still considering a certain tolerance to account for possible production variations and measurement inaccuracies.Potentially required arguments:
robot_pose
: see Hand-eye calibration.Optional arguments:
load_carrier_id
: ID of the load carrier which contains the items to be detected.
load_carrier_compartment
: compartment inside the load carrier where to detect items.
region_of_interest_id
: ifload_carrier_id
is set, ID of the region of interest where to search for the load carriers. Otherwise, ID of the region of interest where to search for the items.Response:
The definition for the response with corresponding datatypes is:
{ "name": "detect_items", "response": { "items": [ { "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "rectangle": { "x": "float64", "y": "float64" }, "timestamp": { "nsec": "int32", "sec": "int32" }, "type": "string", "uuid": "string" } ], "load_carriers": [ { "id": "string", "inner_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "outer_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "overfilled": "bool", "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" } } ], "return_code": { "message": "string", "value": "int16" }, "timestamp": { "nsec": "int32", "sec": "int32" } } }
load_carriers
: list of detected load carriers.
items
: list of detected rectangles.
timestamp
: timestamp of the image set the detection ran on.
return_code
: holds possible warnings or error codes and messages.
compute_grasps
(for ItemPick)¶
Triggers the computation of grasping poses for a suction device as described in Computation of grasps.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_itempick/services/compute_graspsRequest:
The definition for the request arguments with corresponding datatypes is:
{ "args": { "collision_detection": { "gripper_id": "string", "pre_grasp_offset": { "x": "float64", "y": "float64", "z": "float64" } }, "item_models": [ { "type": "string", "unknown": { "max_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "min_dimensions": { "x": "float64", "y": "float64", "z": "float64" } } } ], "load_carrier_compartment": { "box": { "x": "float64", "y": "float64", "z": "float64" }, "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } } }, "load_carrier_id": "string", "pose_frame": "string", "region_of_interest_id": "string", "robot_pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "suction_surface_length": "float64", "suction_surface_width": "float64" } }Required arguments:
pose_frame
: see Hand-eye calibration.
suction_surface_length
: length of the suction device grasping surface.
suction_surface_width
: width of the suction device grasping surface.Potentially required arguments:
robot_pose
: see Hand-eye calibration.Optional arguments:
load_carrier_id
: ID of the load carrier which contains the items to be grasped.
load_carrier_compartment
: compartment inside the load carrier where to compute grasps.
region_of_interest_id
: ifload_carrier_id
is set, ID of the region of interest where to search for the load carriers. Otherwise, ID of the region of interest where to compute grasps.
item_models
: list of unknown items with minimum and maximum dimensions, with the minimum dimensions strictly smaller than the maximum dimensions. Only oneitem_model
of typeUNKNOWN
is currently supported.
collision_detection
: see Collision checking within other modules.Response:
The definition for the response with corresponding datatypes is:
{ "name": "compute_grasps", "response": { "grasps": [ { "item_uuid": "string", "max_suction_surface_length": "float64", "max_suction_surface_width": "float64", "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "quality": "float64", "timestamp": { "nsec": "int32", "sec": "int32" }, "type": "string", "uuid": "string" } ], "load_carriers": [ { "id": "string", "inner_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "outer_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "overfilled": "bool", "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" } } ], "return_code": { "message": "string", "value": "int16" }, "timestamp": { "nsec": "int32", "sec": "int32" } } }
load_carriers
: list of detected load carriers.
grasps
: sorted list of suction grasps.
timestamp
: timestamp of the image set the detection ran on.
return_code
: holds possible warnings or error codes and messages.
compute_grasps
(for BoxPick)¶
Triggers the detection of rectangles and the computation of grasping poses for the detected rectangles as described in Computation of grasps.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/rc_boxpick/services/compute_graspsRequest:
The definition for the request arguments with corresponding datatypes is:
{ "args": { "collision_detection": { "gripper_id": "string", "pre_grasp_offset": { "x": "float64", "y": "float64", "z": "float64" } }, "item_models": [ { "rectangle": { "max_dimensions": { "x": "float64", "y": "float64" }, "min_dimensions": { "x": "float64", "y": "float64" } }, "type": "string" } ], "load_carrier_compartment": { "box": { "x": "float64", "y": "float64", "z": "float64" }, "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } } }, "load_carrier_id": "string", "pose_frame": "string", "region_of_interest_id": "string", "robot_pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "suction_surface_length": "float64", "suction_surface_width": "float64" } }Required arguments:
pose_frame
: see Hand-eye calibration.
item_models
: list of rectangles with minimum and maximum size, with the minimum dimensions strictly smaller than the maximum dimensions. The dimensions should be given fairly accurately to avoid misdetections, while still considering a certain tolerance to account for possible production variations and measurement inaccuracies.
suction_surface_length
: length of the suction device grasping surface.
suction_surface_width
: width of the suction device grasping surface.Potentially required arguments:
robot_pose
: see Hand-eye calibration.Optional arguments:
load_carrier_id
: ID of the load carrier which contains the items to be grasped.
load_carrier_compartment
: compartment inside the load carrier where to compute grasps.
region_of_interest_id
: ifload_carrier_id
is set, ID of the region of interest where to search for the load carriers. Otherwise, ID of the region of interest where to compute grasps.
collision_detection
: see Collision checking within other modules.Response:
The definition for the response with corresponding datatypes is:
{ "name": "compute_grasps", "response": { "grasps": [ { "item_uuid": "string", "max_suction_surface_length": "float64", "max_suction_surface_width": "float64", "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "quality": "float64", "timestamp": { "nsec": "int32", "sec": "int32" }, "type": "string", "uuid": "string" } ], "items": [ { "grasp_uuids": [ "string" ], "pose": { "orientation": { "w": "float64", "x": "float64", "y": "float64", "z": "float64" }, "position": { "x": "float64", "y": "float64", "z": "float64" } }, "pose_frame": "string", "rectangle": { "x": "float64", "y": "float64" }, "timestamp": { "nsec": "int32", "sec": "int32" }, "type": "string", "uuid": "string" } ], "load_carriers": [ { "id": "string", "inner_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "outer_dimensions": { "x": "float64", "y": "float64", "z": "float64" }, "overfilled": "bool", "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" } } ], "return_code": { "message": "string", "value": "int16" }, "timestamp": { "nsec": "int32", "sec": "int32" } } }
load_carriers
: list of detected load carriers.
items
: sorted list of suction grasps on the detected rectangles.
grasps
: sorted list of suction grasps.
timestamp
: timestamp of the image set the detection ran on.
return_code
: holds possible warnings or error codes and messages.
save_parameters
¶
This service saves the currently set parameters persistently. Thereby, the same parameters will still apply after a reboot of the rc_visard. The node parameters are not persistent over firmware updates and rollbacks.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/save_parameters
This service has no arguments.
The definition for the response with corresponding datatypes is:
{ "name": "save_parameters", "response": { "return_code": { "message": "string", "value": "int16" } } }
reset_defaults
¶
This service resets all parameters of the component to its default values, as listed in above table. The reset does not apply to regions of interest and load carriers.
This service can be called as follows.
PUT http://<host>/api/v1/nodes/<rc_itempick|rc_boxpick>/services/save_parameters
This service has no arguments.
The definition for the response with corresponding datatypes is:
{ "name": "reset_defaults", "response": { "return_code": { "message": "string", "value": "int16" } } }