|
1 | 1 | # robot_self_filter |
2 | | -Robot self filter package in ros2 |
| 2 | + |
| 3 | +A ROS 2 package that filters robot body parts from point cloud data, enabling sensors to ignore the robot's own geometry during perception tasks. |
| 4 | + |
| 5 | +## Overview |
| 6 | + |
| 7 | +The `robot_self_filter` package removes points from sensor data that correspond to the robot's body, preventing self-occlusion issues in perception pipelines. It uses the robot's URDF model to create collision shapes and filters out points that fall within these shapes. |
| 8 | + |
| 9 | +### Key Features |
| 10 | + |
| 11 | +- **Multi-sensor support**: Compatible with various LiDAR sensors (Ouster, Hesai, Robosense, Pandar) |
| 12 | +- **Dynamic filtering**: Updates collision shapes based on robot joint states |
| 13 | +- **Configurable shapes**: Supports spheres, boxes, and cylinders with customizable padding and scaling |
| 14 | +- **Visualization**: Publishes collision shapes for debugging and tuning |
| 15 | +- **Performance optimized**: Efficient point cloud processing using PCL |
| 16 | + |
| 17 | +## Installation |
| 18 | + |
| 19 | +### Prerequisites |
| 20 | + |
| 21 | +- ROS 2 (tested on Humble/Iron) |
| 22 | +- Dependencies: |
| 23 | + - `rclcpp` |
| 24 | + - `tf2_ros` |
| 25 | + - `sensor_msgs` |
| 26 | + - `geometry_msgs` |
| 27 | + - `visualization_msgs` |
| 28 | + - `urdf` |
| 29 | + - `resource_retriever` |
| 30 | + - `pcl_ros` |
| 31 | + - `filters` |
| 32 | + - `bullet` |
| 33 | + - `assimp` |
| 34 | + |
| 35 | +### Build |
| 36 | + |
| 37 | +```bash |
| 38 | +cd ~/ros2_ws |
| 39 | +colcon build --packages-select robot_self_filter |
| 40 | +source install/setup.bash |
| 41 | +``` |
| 42 | + |
| 43 | +## Usage |
| 44 | + |
| 45 | +### Quick Start |
| 46 | + |
| 47 | +Launch the self filter node with your robot configuration: |
| 48 | + |
| 49 | +```bash |
| 50 | +ros2 launch robot_self_filter self_filter.launch.py \ |
| 51 | + robot_description:="$(xacro /path/to/robot.urdf.xacro)" \ |
| 52 | + filter_config:=/path/to/filter_config.yaml \ |
| 53 | + in_pointcloud_topic:=/lidar/points \ |
| 54 | + out_pointcloud_topic:=/lidar/points_filtered |
| 55 | +``` |
| 56 | + |
| 57 | +### Launch Parameters |
| 58 | + |
| 59 | +| Parameter | Type | Default | Description | |
| 60 | +|-----------|------|---------|-------------| |
| 61 | +| `robot_description` | string | - | Robot URDF/XACRO description | |
| 62 | +| `filter_config` | string | - | Path to YAML configuration file | |
| 63 | +| `in_pointcloud_topic` | string | `/cloud_in` | Input point cloud topic | |
| 64 | +| `out_pointcloud_topic` | string | `/cloud_out` | Filtered point cloud topic | |
| 65 | +| `lidar_sensor_type` | int | `2` | Sensor type (0: XYZ, 1: XYZRGB, 2: Ouster, 3: Hesai, 4: Robosense, 5: Pandar) | |
| 66 | +| `zero_for_removed_points` | bool | `true` | Set filtered points to zero instead of removing | |
| 67 | +| `use_sim_time` | bool | `true` | Use simulation time | |
| 68 | +| `description_name` | string | `/robot_description` | Robot description parameter namespace | |
| 69 | + |
| 70 | +## Configuration |
| 71 | + |
| 72 | +### YAML Configuration File |
| 73 | + |
| 74 | +The filter configuration is defined in a YAML file. See `params/example.yaml` for a complete example. |
| 75 | + |
| 76 | +#### Basic Structure |
| 77 | + |
| 78 | +```yaml |
| 79 | +self_filter_node: |
| 80 | + ros__parameters: |
| 81 | + sensor_frame: "lidar_frame" # Frame of the sensor |
| 82 | + |
| 83 | + # Default shape parameters |
| 84 | + default_sphere_scale: 1.0 |
| 85 | + default_sphere_padding: 0.01 |
| 86 | + |
| 87 | + default_box_scale: [1.0, 1.0, 1.0] # [x, y, z] |
| 88 | + default_box_padding: [0.01, 0.01, 0.01] # [x, y, z] |
| 89 | + |
| 90 | + default_cylinder_scale: [1.0, 1.0] # [radial, vertical] |
| 91 | + default_cylinder_padding: [0.01, 0.01] # [radial, vertical] |
| 92 | + |
| 93 | + # Filtering parameters |
| 94 | + keep_organized: false # Maintain organized point cloud structure |
| 95 | + zero_for_removed_points: false # Zero points instead of removing |
| 96 | + invert: false # Invert filter (keep only robot points) |
| 97 | + min_sensor_dist: 0.5 # Minimum distance from sensor to filter |
| 98 | + |
| 99 | + # Links to filter |
| 100 | + self_see_links: |
| 101 | + names: |
| 102 | + - base_link |
| 103 | + - arm_link_1 |
| 104 | + - arm_link_2 |
| 105 | + # ... add all robot links to filter |
| 106 | + |
| 107 | + # Per-link custom parameters (optional) |
| 108 | + arm_link_1: |
| 109 | + box_scale: [1.1, 1.1, 1.0] |
| 110 | + box_padding: [0.05, 0.05, 0.02] |
| 111 | +``` |
| 112 | +
|
| 113 | +### Shape Types |
| 114 | +
|
| 115 | +The filter automatically determines shape types from the robot's URDF collision geometry: |
| 116 | +
|
| 117 | +- **Sphere**: Single scale and padding value |
| 118 | +- **Box**: 3D scale and padding values [x, y, z] |
| 119 | +- **Cylinder**: 2D scale and padding [radial, vertical] |
| 120 | +
|
| 121 | +### Tuning Guidelines |
| 122 | +
|
| 123 | +1. **Start with default values**: Use scale=1.0 and small padding (0.01-0.05) |
| 124 | +2. **Visualize collision shapes**: Check `/collision_shapes` topic in RViz |
| 125 | +3. **Adjust per-link parameters**: Fine-tune problematic links individually |
| 126 | +4. **Consider sensor noise**: Increase padding for noisy sensors |
| 127 | +5. **Monitor performance**: Larger padding values may filter valid points |
| 128 | + |
| 129 | +## Topics |
| 130 | + |
| 131 | +### Subscribed Topics |
| 132 | + |
| 133 | +- `<in_pointcloud_topic>` (sensor_msgs/PointCloud2): Raw point cloud from sensor |
| 134 | +- `/tf` (tf2_msgs/TFMessage): Transform data |
| 135 | +- `/tf_static` (tf2_msgs/TFMessage): Static transforms |
| 136 | +- `/joint_states` (sensor_msgs/JointState): Robot joint positions |
| 137 | + |
| 138 | +### Published Topics |
| 139 | + |
| 140 | +- `<out_pointcloud_topic>` (sensor_msgs/PointCloud2): Filtered point cloud |
| 141 | +- `/collision_shapes` (visualization_msgs/MarkerArray): Visualization of filter shapes |
| 142 | + |
| 143 | +## Visualization |
| 144 | + |
| 145 | +To visualize the collision shapes in RViz: |
| 146 | + |
| 147 | +1. Add a MarkerArray display |
| 148 | +2. Set topic to `/collision_shapes` |
| 149 | +3. Collision shapes will appear as semi-transparent geometries |
| 150 | + |
| 151 | +## Sensor Types |
| 152 | + |
| 153 | +The package supports multiple sensor types through the `lidar_sensor_type` parameter: |
| 154 | + |
| 155 | +| Value | Sensor Type | Point Type | |
| 156 | +|-------|-------------|------------| |
| 157 | +| 0 | Generic XYZ | `pcl::PointXYZ` | |
| 158 | +| 1 | Generic XYZRGB | `pcl::PointXYZRGB` | |
| 159 | +| 2 | Ouster | Custom Ouster point type | |
| 160 | +| 3 | Hesai | Custom Hesai point type | |
| 161 | +| 4 | Robosense | Custom Robosense point type | |
| 162 | +| 5 | Pandar | Custom Pandar point type | |
| 163 | + |
| 164 | +## Examples |
| 165 | + |
| 166 | +### Example 1: Mobile Robot with Arm |
| 167 | + |
| 168 | +```yaml |
| 169 | +self_filter_mobile_robot: |
| 170 | + ros__parameters: |
| 171 | + sensor_frame: "lidar_link" |
| 172 | + min_sensor_dist: 0.3 |
| 173 | + |
| 174 | + self_see_links: |
| 175 | + names: |
| 176 | + - base_link |
| 177 | + - wheel_left |
| 178 | + - wheel_right |
| 179 | + - arm_base |
| 180 | + - arm_link_1 |
| 181 | + - arm_link_2 |
| 182 | + - gripper |
| 183 | + |
| 184 | + # Wheels need extra padding for suspension movement |
| 185 | + wheel_left: |
| 186 | + cylinder_scale: [1.0, 1.0] |
| 187 | + cylinder_padding: [0.05, 0.1] |
| 188 | + |
| 189 | + wheel_right: |
| 190 | + cylinder_scale: [1.0, 1.0] |
| 191 | + cylinder_padding: [0.05, 0.1] |
| 192 | +``` |
| 193 | + |
| 194 | +### Example 2: Construction Equipment |
| 195 | + |
| 196 | +See `params/example.yaml` for a complete configuration example for construction equipment with multiple moving parts. |
| 197 | + |
| 198 | +## Troubleshooting |
| 199 | + |
| 200 | +### Common Issues |
| 201 | + |
| 202 | +1. **Points not being filtered** |
| 203 | + - Check sensor frame matches configuration |
| 204 | + - Verify TF tree is complete |
| 205 | + - Increase padding values |
| 206 | + - Check URDF collision geometries |
| 207 | + |
| 208 | +2. **Too many points filtered** |
| 209 | + - Reduce padding values |
| 210 | + - Check scale factors (should typically be 1.0) |
| 211 | + - Verify min_sensor_dist setting |
| 212 | + |
| 213 | +3. **Performance issues** |
| 214 | + - Reduce number of filtered links |
| 215 | + - Simplify collision geometries in URDF |
| 216 | + - Consider using `zero_for_removed_points` for organized clouds |
| 217 | + |
| 218 | +4. **No output point cloud** |
| 219 | + - Verify input topic is publishing |
| 220 | + - Check remappings in launch file |
| 221 | + - Ensure robot_description is loaded |
| 222 | + |
| 223 | +## Contributing |
| 224 | + |
| 225 | +Contributions are welcome! Please ensure your code follows ROS 2 coding standards and includes appropriate documentation. |
| 226 | + |
| 227 | +## License |
| 228 | + |
| 229 | +BSD License - See package.xml for details |
| 230 | + |
| 231 | +## Maintainer |
| 232 | + |
| 233 | +Lorenzo Terenzi <lterenzi@ethz.ch> |
| 234 | + |
| 235 | +## Author |
| 236 | + |
| 237 | +ROS 2 version by Lorenzo Terenzi |
| 238 | +Original ROS 1 version by Eitan Marder-Eppstein |
0 commit comments