Skip to content

Latest commit

 

History

History
60 lines (46 loc) · 3.52 KB

detectors.md

File metadata and controls

60 lines (46 loc) · 3.52 KB

DETECTORS

This file contains some additional information on calbration board detectors.

Lidar detector

The lidar_detector node subscribes to /velodyne_points ROS topic, which is a sensors_msgs::PointCloud2 message. This ROS message contains a point cloud with the Velodyne Point type. This point type additionally contains the ring number of each point. Note: if you do not have a Velodyne Lidar, then you may want to write a converter that adds the ring number.

The lidar_detector publishes two messages:

  • lidar_pattern: point cloud with the four circle centers
  • lidar_pattern_markers: visualization marker with the 4 circle centers in order to visualize the detections in RVIZ.

Note:

  • In the lidar_detector, PCL library constantly throws warnings. These warnings may be ignored if the four circle centers are detected correctly (visulise the detection in RViz).

Stereo detector

The stereo_detector node subscribes to four ROS topics:

  • /ueye/left/image_rect_color: type: sensor_msgs::Image message
  • /ueye/left/camera_info: type: sensor_msgs::CameraInfo message
  • /ueye/right/camera_info: type: sensor_msgs::CameraInfo message
  • /ueye/disparity: type: stereo_msgs::DisparityImage message

The stereo_detector publishes two messages:

  • stereo_pattern: point cloud with the four circle centers
  • stereo_pattern_markers: visualization marker with the 4 circle centers in order to visualize the detections in RVIZ.

Radar detector (2D or 3D)

The radar_detector node subscribes to a ROS topic with the name: /radar_converter/detections. This ROS topic has a message type: radar_msgs::RadarDetectionArray. We assume that X longitudinal and Y is lateral in the radar_msgs::RadarDetectionArray. The detector can work with both 2D and 3D radars, but range is determined only by longitudinal (X) and lateral (Y) position.

You can define a minimum and maximum allowed range and RCS using ROS parameters. Within that RCS+range window, you can choose to select the actual detection either based on lowest/highest range, or lowest/higher RCS. For an example, see the launch file here. The full list of parameters is as follows:

minimum_RCS:float, default: -inf
maximum_RCS:float, default: inf
min_range_object:float, default: -inf
max_range_object:float, default: inf
selection_basis:[rcs or range], default:range
selection_criterion:[min or max], default:min

This node publishes two messages:

  • radar_pattern: point cloud with the calibration board detection (of reflector)
  • radar_marker: visualization marker with the radar detection. This marker can be visualized in RViz. The vertical shape indicates the detection of the reflector at elevation angle equal 0 degrees.

Monocular detector

The mono_detector node subscribes to four ROS topics:

  • /ueye/left/image_rect_color: type: sensor_msgs::Image message
  • /ueye/left/camera_info: type: sensor_msgs::CameraInfo message

The mono_detector publishes one message:

  • mono_pattern: point cloud with the four circle centers

Explanation of inputs

This section explains the inputs to the detectors and optimizer. The config.yaml files for the detectors contain explanations of the input parameters.

NOTE: Make sure that the geometry of the calibration board is known to the detectors:

  • detectors: min_radius, max_radius, radius, width and height in YAML files
  • optimizer: see class geometry_calibration_board in calibration_board.py.

Inputs to optimizer are arrays with x,y,z for lidar and camera and x,y for radar.