|
| 1 | +.. _perceptions: |
| 2 | + |
| 3 | + |
| 4 | +Sensor Input and Perception Handling |
| 5 | +#################################### |
| 6 | + |
| 7 | +In EasyNav, **all sensor input flows through a single component**: the ``SensorsNode``. This node is responsible for: |
| 8 | + |
| 9 | +- subscribing to sensor topics defined in the parameter file, |
| 10 | +- converting sensor data into unified internal formats (e.g., point clouds, images), |
| 11 | +- organizing and storing perceptions into groups (e.g., `"points"`, `"image"`), |
| 12 | +- publishing a fused view (optional), |
| 13 | +- writing the current valid perceptions into the `NavState` under their corresponding group key. |
| 14 | + |
| 15 | +Sensor Configuration |
| 16 | +-------------------- |
| 17 | + |
| 18 | +Sensors are defined via ROS 2 parameters under the `sensors_node` configuration. For example: |
| 19 | + |
| 20 | +.. code-block:: yaml |
| 21 | +
|
| 22 | + sensors_node: |
| 23 | + ros__parameters: |
| 24 | + use_sim_time: true |
| 25 | + forget_time: 0.5 |
| 26 | + sensors: [laser1, camera1] |
| 27 | + perception_default_frame: odom |
| 28 | + laser1: |
| 29 | + topic: /scan_raw |
| 30 | + type: sensor_msgs/msg/LaserScan |
| 31 | + group: points |
| 32 | + camera1: |
| 33 | + topic: /rgbd_camera/points |
| 34 | + type: sensor_msgs/msg/PointCloud2 |
| 35 | + group: points |
| 36 | +
|
| 37 | +All distance sensors (e.g., `LaserScan`, `PointCloud2`) must be grouped under the `"points"` group. These are converted internally into **`PointPerception`** instances and aggregated into a single structure called **`PointPerceptions`**, which is written into the `NavState` under the key `"points"`. |
| 38 | + |
| 39 | +If image data is included: |
| 40 | + |
| 41 | +.. code-block:: yaml |
| 42 | +
|
| 43 | + image1: |
| 44 | + topic: /rgbd_camera/image_raw |
| 45 | + type: sensor_msgs/msg/Image |
| 46 | + group: image |
| 47 | +
|
| 48 | +Then the group `"image"` will appear in the `NavState`, using the `ImagePerception` type. |
| 49 | + |
| 50 | +Processing Point Perceptions |
| 51 | +---------------------------- |
| 52 | + |
| 53 | +To work with fused or filtered 3D points, EasyNav provides the utility class **`PointPerceptionsOpsView`**. |
| 54 | + |
| 55 | +You typically retrieve the `PointPerceptions` from the `NavState`: |
| 56 | + |
| 57 | +.. code-block:: cpp |
| 58 | +
|
| 59 | + if (!nav_state.has("points")) return; |
| 60 | + const auto perceptions = nav_state.get<PointPerceptions>("points"); |
| 61 | +
|
| 62 | +Then create an operations view: |
| 63 | + |
| 64 | +.. code-block:: cpp |
| 65 | +
|
| 66 | + PointPerceptionsOpsView view(perceptions); |
| 67 | +
|
| 68 | +The view provides a fluent interface to manipulate the point cloud. There are two kinds of operations: |
| 69 | + |
| 70 | +- **Lightweight operations**: these return a reference (`PointPerceptionsOpsView &`) and operate on views without copying data. |
| 71 | +- **Heavyweight operations**: these return a `std::shared_ptr<PointPerceptionsOpsView>` and typically involve transformations or filtering that produce new point sets. |
| 72 | + |
| 73 | +Common operations include: |
| 74 | + |
| 75 | +.. code-block:: cpp |
| 76 | +
|
| 77 | + auto downsampled = PointPerceptionsOpsView(perceptions) |
| 78 | + .downsample(0.2); // reduce density (heavy) |
| 79 | +
|
| 80 | + auto fused = downsampled |
| 81 | + ->fuse("base_link"); // transform all points to base_link (heavy) |
| 82 | +
|
| 83 | + auto filtered = fused |
| 84 | + ->filter({-1.0, -1.0, 0.0}, {1.0, 1.0, 2.0}); // spatial crop (heavy) |
| 85 | +
|
| 86 | + auto points = filtered->as_points(); // retrieve std::vector<Point3D> |
| 87 | +
|
| 88 | +Operation Summary |
| 89 | +----------------- |
| 90 | + |
| 91 | ++--------------------+----------------------------+------------------------------------------+ |
| 92 | +| Operation | Return Type | Description | |
| 93 | ++====================+============================+==========================================+ |
| 94 | +| `filter(...)` | `std::shared_ptr<...>` | Filters points inside a bounding box | |
| 95 | ++--------------------+----------------------------+------------------------------------------+ |
| 96 | +| `downsample(res)` | `std::shared_ptr<...>` | Voxel downsampling | |
| 97 | ++--------------------+----------------------------+------------------------------------------+ |
| 98 | +| `fuse(frame)` | `std::shared_ptr<...>` | Transforms all perceptions to a frame | |
| 99 | ++--------------------+----------------------------+------------------------------------------+ |
| 100 | +| `collapse()` | `std::shared_ptr<...>` | Merge similar points into one | |
| 101 | ++--------------------+----------------------------+------------------------------------------+ |
| 102 | +| `as_points()` | `std::vector<Point3D>` | Exports data as raw 3D point list | |
| 103 | ++--------------------+----------------------------+------------------------------------------+ |
| 104 | + |
| 105 | +Example: Updating a Map |
| 106 | +----------------------- |
| 107 | + |
| 108 | +Many components use fused and filtered points to update occupancy or elevation maps: |
| 109 | + |
| 110 | +.. code-block:: cpp |
| 111 | +
|
| 112 | + const auto perceptions = nav_state.get<PointPerceptions>("points"); |
| 113 | +
|
| 114 | + auto fused = PointPerceptionsOpsView(perceptions) |
| 115 | + .downsample(dynamic_map_.resolution()) // reduce point density |
| 116 | + .fuse("map") // transform to map frame |
| 117 | + ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) // ignore ground clutter |
| 118 | + .as_points(); |
| 119 | +
|
| 120 | + for (const auto & p : fused) { |
| 121 | + if (dynamic_map_.check_bounds_metric(p.x, p.y)) { |
| 122 | + auto [cx, cy] = dynamic_map_.metric_to_cell(p.x, p.y); |
| 123 | + dynamic_map_.at(cx, cy) = 1; |
| 124 | + } |
| 125 | + } |
| 126 | +
|
| 127 | +Fused Visualization |
| 128 | +------------------- |
| 129 | + |
| 130 | +If the `SensorsNode` has subscribers on its output topic, it will publish the fused perception result after processing: |
| 131 | + |
| 132 | +.. code-block:: cpp |
| 133 | +
|
| 134 | + if (percept_pub_->get_subscription_count() > 0) { |
| 135 | + auto fused = PointPerceptionsOpsView(perceptions) |
| 136 | + .fuse(perception_default_frame_); |
| 137 | +
|
| 138 | + auto fused_points = fused->as_points(); |
| 139 | + auto msg = points_to_rosmsg(fused_points); |
| 140 | +
|
| 141 | + msg.header.frame_id = perception_default_frame_; |
| 142 | + msg.header.stamp = fused->get_perceptions()[0]->stamp; |
| 143 | + percept_pub_->publish(msg); |
| 144 | + } |
| 145 | +
|
| 146 | +Extending to Other Modalities |
| 147 | +----------------------------- |
| 148 | + |
| 149 | +In addition to `"points"` and `"image"`, developers can add new groups and corresponding `PerceptionBase`-derived classes. All perceptions: |
| 150 | + |
| 151 | +- inherit from `PerceptionBase`, |
| 152 | +- have a `stamp`, `frame_id`, and `valid` flag, |
| 153 | +- are grouped by semantic label (e.g., `"points"`), |
| 154 | +- are automatically managed by the `SensorsNode`. |
| 155 | + |
| 156 | +--- |
| 157 | + |
| 158 | +This unified and extensible perception handling design allows plugins to focus on **what** data they need, not **how** it was acquired, filtered, or transformed. |
0 commit comments