Skip to content

all_seaing_perception

Panagiotis Liampas edited this page Dec 15, 2024 · 13 revisions

Nodes

color_segmentation.py

Works best in simulation for detecting buoys. The node subscribes to camera images and performs color segmentation to detect buoys. The detected buoys are then published as bounding boxes.

Subscribed topics:

  • image (raw image from camera, can/will be remapped): a sensor_msgs/Image message containing the camera image to perform color segmentation on.

Published topics:

  • /bounding_boxes: an [all_seaing_interfaces/LabeledBoundingBox2DArray] message containing the bounding boxes of each of the masks detected.
  • image/segmented: a sensor_msgs/Image message containing the camera image with bounding boxes overlayed. This is useful for debugging.

Parameters:

  • color_ranges_file: a string parameter, defaults to ''. The file path to the config file that contains HSV min/max values for each color.
  • color_label_mappings_file: a string parameter, defaults to ''. The file path to the config file that contains the mapping between color and buoy object label.

obstacle_bbox_overlay

Overlays obstacles in the obstacle map and bounding boxes from obstacle detection. The overlay allows labeling of the obstacles, and a new map is published with the labeled obstacles.

Subscribed topics:

Published topics:

obstacle_detector

Clusters the input point cloud into obstacles using the euclidean clustering algorithm. The clusters are also tracked over time. Both raw and tracked clusters of obstacles (local/global position and convex hull) are published, along with the point cloud of the raw clusters.

Subscribed topics:

  • /in_cloud: an input sensor_msgs/PointCloud2 message to cluster. Typically published by the pointcloud_filter node, but can be directly used from the LiDAR.
  • /odometry/filtered: a nav_msgs/Odometry message containing the robot (x, y) position. These coordinates are used when tracking the clusters, since tracking using global position of the obstacles is much more accurate when tracking using local position.

Published topics:

Parameters:

  • obstacle_size_min: an integer parameter, defaults to 20. The minimum number of points required for a cluster.
  • obstacle_size_max: an integer parameter, defaults to 100000. The maximum number of points in a cluster.
  • clustering_distance: a double parameter, defaults to 0.75. Points closer to each other than this value (in meters) are considered as one obstacle.
  • obstacle_seg_thresh: a double parameter, defaults to 1.0. When tracking obstacles, if a raw obstacle is farther than this value (in meters) than the tracked obstacles, then the raw obstacle is considered a new obstacle and is added to the tracked obstacles.
  • obstacle_drop_thresh: a double parameter, defaults to 1.0. If the same obstacle is not found for over this time, it is dropped from the tracked clusters.
  • polygon_area_thresh: a double parameter, defaults to 100000.0. Obstacles with convex hull greater than this area (in meters squared) is filtered.
  • viz: a boolean parameter, defaults to true. If true, RVIZ markers are published for visualization.

pointcloud_filter

Filters and downsamples a point cloud based on range and intensity. Filtered and/or downsampled point cloud may be preferred when clustering.

Subscribed topics:

Published topics:

Parameters:

  • range_min_threshold: a double parameter, defaults to 0.0. All points with range less than this value gets filtered.
  • range_max_threshold: a double parameter, defaults to 100000.0. All points with range greater than this value gets filtered.
  • intensity_low_threshold: a double parameter, defaults to 0.0. All points with intensity less than this value gets filtered.
  • intensity_high_threshold: a double parameter, defaults to 100000.0. All points with intensity greater than this value gets filtered.
  • leaf_size: a double parameter, defaults to 0.0. The size (in meters) of the 3D voxel grids when downsampling. If set to 0 (default), this node doesn't downsample.
  • hfov: a double parameter, defaults to 0.0. The angle in degrees (0-180) in front of the boat which gets used. All points outside this angle gets filtered. If set to 0 (default), this node doesn't filter based on angle.

pointcloud_image_overlay

Projects a point cloud onto a camera image. Transforms point cloud data from the LiDAR frame to the camera frame with the extrinsic matrix and projects the transformed point cloud onto the camera image with the intrinsic matrix calculated from the given camera information.

Subscribed topics:

  • /img_src: a sensor_msgs/Image message containing the camera image to fuse.
  • /cloud_src: a sensor_msgs/PointCloud2 message containing the LiDAR pointcloud to fuse.
  • /img_info_src: a sensor_msgs/CameraInfo message containing camera information such as focal length and optical center to calculate the intrinsic matrix.

Published topics:

  • /pc_image_fusion: a sensor_msgs/Image message containing the given camera image with the projected LiDAR points.

bbox_project_pcloud

Projects the bounding boxes onto the point cloud (actually does the opposite, projects the point cloud points onto the image and checking if they are within a bounding box) and selecting the points that are in the bounding box of each object, creating a set of point clouds matched to detected objects from the camera. Then, it clusters (based on color difference and euclidean distance) the points that are in each object's point cloud, and performs color segmentation on the image depending on the color that YOLOv8/color segmentation algorithm detected, creating multiple clusters and contours, between which it then takes the optimal pair based on an optimality metric that takes into account the similarity to the color detected by YOLOv8, the distance between the cluster points when projected onto the image and the color segment points, and the size of the cluster and the color segments, thus selecting the cluster and color segment that best correspond to the object detected.

Subscribed topics:

Published Topics:

Parameters:

  • bbox_object_margin: the margin to add to the detected object's bounding box when checking if a projected 3D point is in it, defaults to 0.0
  • color_label_mappings_file: the path to the YAML file containing the mappings from colors to labels, defaults to all_seaing_bringup/config/perception/color_label_mappings.yaml
  • matching_weights_file: the path to the YAML file containing the weights of aspects of the optimality metric used to select the best cluster-image segment pair, defaults to all_seaing_bringup/config/perception/matching_weights.yaml
  • contour_matching_color_ranges_file: the path to the YAML file containing the mappings from colors to HSV value ranges for color segmentation and cluster-contour optimization/matching, defaults to all_seaing_bringup/config/perception/contour_matching_color_ranges_file.yaml
  • obstacle_size_min: the minimum number of points a detected cluster should have, defaults to 20
  • obstacle_size_max: the maximum number of points a detected cluster should have, defaults to 100000
  • clustering_distance: the maximum distance a point that's added to a cluster should have from at least one point already in it, defaults to 0.75