LoadCarrier

Introduction

The LoadCarrier module allows the detection of load carriers, which is usually the first step when objects or grasp points inside a bin should be found. The models of the load carriers to be detected have to be defined in the LoadCarrierDB module.

The LoadCarrier module is an optional on-board module of the rc_cube and is licensed with any of the modules ItemPick and BoxPick or CADMatch and SilhouetteMatch. Otherwise it requires a separate LoadCarrier license to be purchased.

Note

This module is pipeline specific. Changes to its settings or parameters only affect the respective camera pipeline and have no influence on other pipelines running on the rc_cube.

Detection of load carriers

The load carrier detection algorithm detects load carriers that match a specific load carrier model, which must be defined in the LoadCarrierDB module. The load carrier model is referenced by its ID, which is passed to the load carrier detection. The detection of a load carrier is based on the detection of its rectangular rim. For this, it uses lines detected in the left camera image and the depth values of the load carrier rim. Thus, the rim should form a contrast to the background and the disparity image must be dense on the rim.

If multiple load carriers of the specified load carrier ID are visible in the scene, all of them will be detected and returned by the load carrier detection.

By default, when assume_gravity_aligned is true and gravity measurements are available, the algorithm searches for load carriers whose rim planes are perpendicular to the measured gravity vector. To detect tilted load carriers, assume_gravity_aligned must be set to false or the load carrier’s approximate orientation must be specified as pose and the pose_type should be set to ORIENTATION_PRIOR.

Load carriers can be detected at a distance of up to 3 meters from the camera.

When a 3D region of interest (see RoiDB) is used to limit the volume in which load carriers should be detected, only the load carriers’ rims must be fully included in the region of interest.

The detection algorithm returns the poses of the load carriers’ origins (see Load carrier definition) in the desired pose frame.

The detection functionality also determines if the detected load carriers are overfilled, which means, that objects protrude from the plane defined by the load carrier’s outer part of the rim.

_images/itempick_load_carrier_reference_rim_sidebyside.svg

Fig. 13 Load carrier models and reference frames

Detection of filling level

The LoadCarrier module offers the detect_filling_level service to compute the filling level of all detected load carriers.

The load carriers are subdivided into a configurable number of cells in a 2D grid. The maximum number of cells is 10x10. For each cell, the following values are reported:

  • level_in_percent: minimum, maximum and mean cell filling level in percent from the load carrier floor. These values can be larger than 100% if the cell is overfilled.
  • level_free_in_meters: minimum, maximum and mean cell free level in meters from the load carrier rim. These values can be negative if the cell is overfilled.
  • cell_size: dimensions of the 2D cell in meters.
  • cell_position: position of the cell center in meters (either in camera or external frame, see Hand-eye calibration). The z-coordinate is on the level of the load carrier rim.
  • coverage: represents the proportion of valid pixels in this cell. It varies between 0 and 1 with steps of 0.1. A low coverage indicates that the cell contains several missing data (i.e. only a few points were actually measured in this cell).

These values are also calculated for the whole load carrier itself. If no cell subdivision is specified, only the overall filling level is computed.

_images/itempick_lc_filling_level.png

Fig. 14 Visualizations of the load carrier filling level: overall filling level without grid (left), 4x3 grid (center), 8x8 grid (right). The load carrier content is shown in a green gradient from white (on the load carrier floor) to dark green. The overfilled regions are visualized in red. Numbers indicate cell IDs.

Interaction with other modules

Internally, the LoadCarrier module depends on, and interacts with other on-board modules as listed below.

Note

All changes and configuration updates to these modules will affect the performance of the LoadCarrier module.

Stereo camera and Stereo matching

The LoadCarrier module makes internally use of the following data:

  • Rectified images from the Camera module (rc_camera);
  • Disparity, error, and confidence images from the Stereo matching module (rc_stereomatching).

All processed images are guaranteed to be captured after the module trigger time.

IO and Projector Control

In case the rc_cube is used in conjunction with an external random dot projector and the IO and Projector Control module (rc_iocontrol), it is recommended to connect the projector to GPIO Out 1 and set the stereo-camera module’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.

No additional changes are required to use the LoadCarrier module in combination with a random dot projector.

Hand-eye calibration

In case the camera has been calibrated to a robot, the loadcarrier module can automatically provide poses in the robot coordinate frame. For the loadcarrier nodes’ Services, the frame of the output poses can be controlled with the pose_frame argument.

Two different pose_frame values can be chosen:

  1. Camera frame (camera). All poses provided by the modules 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 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).
  2. External frame (external). All poses provided by the modules are in the external frame, configured by the user during the hand-eye calibration process. The module relies on the on-board Hand-eye calibration module 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, the robot_pose is required to transform poses to and from the external 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.

Parameters

The LoadCarrier module is called rc_load_carrier in the REST-API and is represented in the Web GUIin the desired pipeline under Modules ‣ LoadCarrier. The user can explore and configure the LoadCarrier module’s run-time parameters, e.g. for development and testing, using the Web GUI or the REST-API interface.

Parameter overview

Note

The default values in the parameter table below show the values of the rc_visard. The values can be different for other sensors.

This module offers the following run-time parameters:

Table 11 The rc_load_carrier module’s run-time parameters
Name Type Min Max Default Description
assume_gravity_aligned bool false true true When true, only gravity-aligned load carriers are detected, if gravity measurement is available.
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
min_plausibility float64 0.0 0.99 0.8 Indicates how much of the plane surrounding the load carrier rim must be free to count as valid detection
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

Description of run-time parameters

Each run-time parameter is represented by a row on the LoadCarrier Settings section of the Web GUI’s LoadCarrier page under Modules. 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. The parameters are prefixed with load_carrier_ when they are used outside the rc_load_carrier module from another detection module using the REST-API interface.

assume_gravity_aligned (Assume Gravity Aligned)

If this parameter is set to true, then only load carriers without tilt will be detected. This can speed up the detection. If this parameter is set to false, tilted load carriers will also be detected.

This parameter is ignored for load carriers with an orientation prior.

Note

Gravity alignment is only available for pipelines of type rc_visard. The gravity vector is estimated from linear acceleration readings from the on-board IMU.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/parameters?assume_gravity_aligned=<value>
PUT http://<host>/api/v1/nodes/rc_load_carrier/parameters?assume_gravity_aligned=<value>

model_tolerance (Model Tolerance)

indicates how much the estimated load carrier dimensions are allowed to differ from the load carrier model dimensions in meters.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/parameters?model_tolerance=<value>
PUT http://<host>/api/v1/nodes/rc_load_carrier/parameters?model_tolerance=<value>

crop_distance (Crop Distance)

sets the safety margin in meters by which the load carrier’s inner dimensions are reduced to define the region of interest for detection (ref. Fig. 46).

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/parameters?crop_distance=<value>
PUT http://<host>/api/v1/nodes/rc_load_carrier/parameters?crop_distance=<value>

min_plausibility (Minimum Plausibility):

The minimum plausibility defines how much of the plane around the load carrier rim must at least be free to count as valid detection. Increase the minimal plausibility to reject false positive detections and decrease the value in case a clearly visible load carrier cannot be detected.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/parameters?min_plausibility=<value>
PUT http://<host>/api/v1/nodes/rc_load_carrier/parameters?min_plausibility=<value>

Status values

The LoadCarrier module reports the following status values:

Table 12 The rc_load_carrier module’s status values
Name Description
data_acquisition_time Time in seconds required to acquire image pair
last_timestamp_processed The timestamp of the last processed image pair
load_carrier_detection_time Processing time of the last detection in seconds

Services

The user can explore and call the LoadCarrier module’s services, e.g. for development and testing, using the REST-API interface or the rc_cube Web GUI on the LoadCarrier page under Modules.

The LoadCarrier module offers the following services.

detect_load_carriers

Triggers a load carrier detection as described in Detection of load carriers.

Details

This service can be called as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/services/detect_load_carriers
PUT http://<host>/api/v1/nodes/rc_load_carrier/services/detect_load_carriers

Required arguments:

pose_frame: see Hand-eye calibration.

load_carrier_ids: IDs of the load carriers which should be detected. Currently only one ID can be specified.

Potentially required arguments:

robot_pose: see Hand-eye calibration.

Optional arguments:

region_of_interest_id: ID of the 3D region of interest where to search for the load carriers.

region_of_interest_2d_id: ID of the 2D region of interest where to search for the load carriers.

Note

Only one type of region of interest can be set.

The definition for the request arguments with corresponding datatypes is:

{
  "args": {
    "load_carrier_ids": [
      "string"
    ],
    "pose_frame": "string",
    "region_of_interest_2d_id": "string",
    "region_of_interest_id": "string",
    "robot_pose": {
      "orientation": {
        "w": "float64",
        "x": "float64",
        "y": "float64",
        "z": "float64"
      },
      "position": {
        "x": "float64",
        "y": "float64",
        "z": "float64"
      }
    }
  }
}

load_carriers: list of detected load carriers.

timestamp: timestamp of the image set the detection ran on.

return_code: holds possible warnings or error codes and messages.

The definition for the response with corresponding datatypes is:

{
  "name": "detect_load_carriers",
  "response": {
    "load_carriers": [
      {
        "height_open_side": "float64",
        "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_ledge": {
          "x": "float64",
          "y": "float64"
        },
        "rim_step_height": "float64",
        "rim_thickness": {
          "x": "float64",
          "y": "float64"
        },
        "type": "string"
      }
    ],
    "return_code": {
      "message": "string",
      "value": "int16"
    },
    "timestamp": {
      "nsec": "int32",
      "sec": "int32"
    }
  }
}

detect_filling_level

Triggers a load carrier filling level detection as described in Detection of filling level.

Details

This service can be called as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/services/detect_filling_level
PUT http://<host>/api/v1/nodes/rc_load_carrier/services/detect_filling_level

Required arguments:

pose_frame: see Hand-eye calibration.

load_carrier_ids: IDs of the load carriers which should be detected. Currently only one ID can be specified.

Potentially required arguments:

robot_pose: see Hand-eye calibration.

Optional arguments:

filling_level_cell_count: Number of cells in the filling level grid.

region_of_interest_id: ID of the 3D region of interest where to search for the load carriers.

region_of_interest_2d_id: ID of the 2D region of interest where to search for the load carriers.

Note

Only one type of region of interest can be set.

The definition for the request arguments with corresponding datatypes is:

{
  "args": {
    "filling_level_cell_count": {
      "x": "uint32",
      "y": "uint32"
    },
    "load_carrier_ids": [
      "string"
    ],
    "pose_frame": "string",
    "region_of_interest_2d_id": "string",
    "region_of_interest_id": "string",
    "robot_pose": {
      "orientation": {
        "w": "float64",
        "x": "float64",
        "y": "float64",
        "z": "float64"
      },
      "position": {
        "x": "float64",
        "y": "float64",
        "z": "float64"
      }
    }
  }
}

load_carriers: list of detected load carriers and their filling levels.

timestamp: timestamp of the image set the detection ran on.

return_code: holds possible warnings or error codes and messages.

The definition for the response with corresponding datatypes is:

{
  "name": "detect_filling_level",
  "response": {
    "load_carriers": [
      {
        "cells_filling_levels": [
          {
            "cell_position": {
              "x": "float64",
              "y": "float64",
              "z": "float64"
            },
            "cell_size": {
              "x": "float64",
              "y": "float64"
            },
            "coverage": "float64",
            "level_free_in_meters": {
              "max": "float64",
              "mean": "float64",
              "min": "float64"
            },
            "level_in_percent": {
              "max": "float64",
              "mean": "float64",
              "min": "float64"
            }
          }
        ],
        "filling_level_cell_count": {
          "x": "uint32",
          "y": "uint32"
        },
        "height_open_side": "float64",
        "id": "string",
        "inner_dimensions": {
          "x": "float64",
          "y": "float64",
          "z": "float64"
        },
        "outer_dimensions": {
          "x": "float64",
          "y": "float64",
          "z": "float64"
        },
        "overall_filling_level": {
          "cell_position": {
            "x": "float64",
            "y": "float64",
            "z": "float64"
          },
          "cell_size": {
            "x": "float64",
            "y": "float64"
          },
          "coverage": "float64",
          "level_free_in_meters": {
            "max": "float64",
            "mean": "float64",
            "min": "float64"
          },
          "level_in_percent": {
            "max": "float64",
            "mean": "float64",
            "min": "float64"
          }
        },
        "overfilled": "bool",
        "pose": {
          "orientation": {
            "w": "float64",
            "x": "float64",
            "y": "float64",
            "z": "float64"
          },
          "position": {
            "x": "float64",
            "y": "float64",
            "z": "float64"
          }
        },
        "pose_frame": "string",
        "rim_ledge": {
          "x": "float64",
          "y": "float64"
        },
        "rim_step_height": "float64",
        "rim_thickness": {
          "x": "float64",
          "y": "float64"
        },
        "type": "string"
      }
    ],
    "return_code": {
      "message": "string",
      "value": "int16"
    },
    "timestamp": {
      "nsec": "int32",
      "sec": "int32"
    }
  }
}

reset_defaults

Restores and applies the default values for this module’s parameters (“factory reset”).

Details

This service can be called as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/services/reset_defaults
PUT http://<host>/api/v1/nodes/rc_load_carrier/services/reset_defaults
This service has no arguments.

The definition for the response with corresponding datatypes is:

{
  "name": "reset_defaults",
  "response": {
    "return_code": {
      "message": "string",
      "value": "int16"
    }
  }
}

trigger_dump

Triggers dumping of the detection that corresponds to the given timestamp, or the latest detection, if no timestamp is given. The dumps are saved to the connected USB drive.

Details

This service can be called as follows.

PUT http://<host>/api/v2/pipelines/<0,1,2,3>/nodes/rc_load_carrier/services/trigger_dump
PUT http://<host>/api/v1/nodes/rc_load_carrier/services/trigger_dump

The definition for the request arguments with corresponding datatypes is:

{
  "args": {
    "comment": "string",
    "timestamp": {
      "nsec": "int32",
      "sec": "int32"
    }
  }
}

The definition for the response with corresponding datatypes is:

{
  "name": "trigger_dump",
  "response": {
    "return_code": {
      "message": "string",
      "value": "int16"
    }
  }
}

set_load_carrier (deprecated)

Persistently stores a load carrier on the rc_cube.

This service is not available in API version 2. Use set_load_carrier in rc_load_carrier_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/set_load_carrier

The definitions of the request and response are the same as described in set_load_carrier in rc_load_carrier_db.

get_load_carriers (deprecated)

Returns the configured load carriers with the requested load_carrier_ids.

This service is not available in API version 2. Use get_load_carriers in rc_load_carrier_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/get_load_carriers

The definitions of the request and response are the same as described in get_load_carriers in rc_load_carrier_db.

delete_load_carriers (deprecated)

Deletes the configured load carriers with the requested load_carrier_ids.

This service is not available in API version 2. Use delete_load_carriers in rc_load_carrier_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/delete_load_carriers

The definitions of the request and response are the same as described in delete_load_carriers in rc_load_carrier_db.

set_region_of_interest (deprecated)

Persistently stores a 3D region of interest on the rc_cube.

This service is not available in API version 2. Use set_region_of_interest in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/set_region_of_interest

The definitions of the request and response are the same as described in set_region_of_interest in rc_roi_db.

get_regions_of_interest (deprecated)

Returns the configured 3D regions of interest with the requested region_of_interest_ids.

This service is not available in API version 2. Use get_regions_of_interest in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/get_regions_of_interest

The definitions of the request and response are the same as described in get_regions_of_interest in rc_roi_db.

delete_regions_of_interest (deprecated)

Deletes the configured 3D regions of interest with the requested region_of_interest_ids.

This service is not available in API version 2. Use delete_regions_of_interest in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/delete_regions_of_interest

The definitions of the request and response are the same as described in delete_regions_of_interest in rc_roi_db.

set_region_of_interest_2d (deprecated)

Persistently stores a 2D region of interest on the rc_cube.

This service is not available in API version 2. Use set_region_of_interest_2d in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/set_region_of_interest_2d

The definitions of the request and response are the same as described in set_region_of_interest_2d in rc_roi_db.

get_regions_of_interest_2d (deprecated)

Returns the configured 2D regions of interest with the requested region_of_interest_2d_ids.

This service is not available in API version 2. Use get_regions_of_interest_2d in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/get_region_of_interest_2d

The definitions of the request and response are the same as described in get_regions_of_interest_2d in rc_roi_db.

delete_regions_of_interest_2d (deprecated)

Deletes the configured 2D regions of interest with the requested region_of_interest_2d_ids.

This service is not available in API version 2. Use delete_regions_of_interest_2d in rc_roi_db instead.

This service can be called as follows.

PUT http://<host>/api/v1/nodes/rc_load_carrier/services/delete_regions_of_interest_2d

The definitions of the request and response are the same as described in delete_regions_of_interest_2d in rc_roi_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:

Table 13 Return codes of the LoadCarrier module’s services
Code Description
0 Success
-1 An invalid argument was provided
-4 Data acquisition took longer than allowed
-10 New element could not be added as the maximum storage capacity of load carriers has been exceeded
-11 Sensor not connected, not supported or not ready
-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 has been reached
11 An existent persistent model was overwritten by the call to set_load_carrier
100 The requested load carriers were not detected in the scene
102 The detected load carrier is empty
300 A valid robot_pose was provided as argument but it is not required