-
Notifications
You must be signed in to change notification settings - Fork 232
Add collision detector documentation #451
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Merged
Merged
Changes from all commits
Commits
Show all changes
11 commits
Select commit
Hold shift + click to select a range
1654d5b
Add collision detector docu
ce634f8
fixes
40f9ed3
fix
24c7f57
fix
c73e6ef
fixes
8110ecb
fix references
bd34e9d
fix
bcd0d2a
fixes
0aff0d1
fixes
6eeca72
fix
6a23c6a
fixes
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
301 changes: 301 additions & 0 deletions
301
configuration/packages/collision_monitor/configuring-collision-detector-node.rst
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,301 @@ | ||
| .. _configuring_collision_detector_node: | ||
|
|
||
| Collision Detector Node | ||
| ####################### | ||
|
|
||
| The Collision Detector is a node similar to the Collision Monitor, so it is recommended to read the :ref:`collision_monitor_tutorial` tutorial first. | ||
|
|
||
| In some cases, the user may want to be informed about the detected obstacles without affecting the robot's velocity and instead take a different action within an external node. For example, the user may want to blink LEDs or sound an alarm when the robot is close to an obstacle. | ||
| Another use case could be to detect data points in particular regions (e.g extremely close to the sensor) and warn of malfunctioning sensors. For this purpose, the Collision Detector node was introduced. | ||
| It works similarly to the Collision Monitor, but does not affect the robot's velocity. It will only inform that data from the configured sources has been detected within the configured polygons via message to the ``collision_detector_state`` topic. | ||
|
|
||
| See the package's ``README`` for more information. | ||
|
|
||
| Features | ||
| ******** | ||
|
|
||
| Similarly to the Collision Monitor, the Collision Detector uses robot's relative polygons to define "zones". | ||
| However, unlike the Collision Monitor that uses different behavior models, the Collision Detector does not use any of them and therefore the `action_type` should always be set to `none`. If set to anything else, it will throw an error | ||
|
|
||
| The zones around the robot and the data sources are the same as for the Collision Monitor, with the exception of the footprint polygon, which is not supported by the Collision Detector. | ||
|
|
||
| Parameters | ||
| ********** | ||
|
|
||
| :frequency: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double 10.0 | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Frequency of the main loop that checks for detections. | ||
|
|
||
| :base_frame_id: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string "base_footprint" | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Robot base frame. | ||
|
|
||
| :odom_frame_id: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string "odom" | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Which frame to use for odometry. | ||
|
|
||
| :transform_tolerance: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double 0.1 | ||
| ============== ============================= | ||
|
|
||
| Description | ||
| Time with which to post-date the transform that is published, to indicate that this transform is valid into the future. | ||
|
|
||
| :source_timeout: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double 2.0 | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Maximum time interval in which source data is considered as valid. | ||
|
|
||
| :base_shift_correction: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| bool True | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Whether to correct source data towards to base frame movement, considering the difference between current time and latest source time. If enabled, produces more accurate sources positioning in the robot base frame, at the cost of slower performance. This will cause average delays for ``~1/(2*odom_rate)`` per each ``cmd_vel`` calculation cycle. However, disabling this option for better performance is not recommended for the fast moving robots, where during the typical rate of data sources, robot could move unacceptably far. Thus reasonable odometry rates are recommended (~100 hz). | ||
|
|
||
| :polygons: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| vector<string> N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| List of zones to check for data points. Causes an error, if not specialized. | ||
|
|
||
|
|
||
| :observation_sources: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| vector<string> N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| List of data sources (laser scanners, pointclouds, etc...). Causes an error, if not specialized. | ||
|
|
||
| Polygons parameters | ||
| =================== | ||
|
|
||
| ``<polygon name>`` is the corresponding polygon name ID selected for this type. | ||
|
|
||
| :``<polygon_name>``.type: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Type of polygon shape. Available values are ``polygon``, ``circle``. Causes an error, if not specialized. | ||
|
|
||
| :``<polygon_name>``.points: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| vector<double> N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Polygon vertexes, listed in ``{p1.x, p1.y, p2.x, p2.y, p3.x, p3.y, ...}`` format (e.g. ``{0.5, 0.25, 0.5, -0.25, 0.0, -0.25, 0.0, 0.25}`` for the square in the front). Used for ``polygon`` type. Minimum 3 points for a triangle polygon. If not specified, the collision detector will use dynamic polygon subscription to ``polygon_sub_topic`` | ||
|
|
||
| :``<polygon_name>``.polygon_sub_topic: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Topic to listen the polygon points from. Causes an error, if not specified **and** points are also not specified. If both ``points`` and ``polygon_sub_topic`` are specified, the static ``points`` takes priority. | ||
|
|
||
| :``<polygon_name>``.radius: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Circle radius. Used for ``circle`` type. Causes an error, if not specialized. | ||
|
|
||
| :``<polygon_name>``.action_type: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string N/A | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Only ``none`` action type is supported (more options available for collision monitor) | ||
|
|
||
| :``<polygon_name>``.min_points: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| int 4 | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Minimum number of data readings within a zone to trigger the action. Former ``max_points`` parameter for Humble, that meant the maximum number of data readings within a zone to not trigger the action). ``min_points`` is equal to ``max_points + 1`` value. | ||
|
|
||
| :``<polygon_name>``.visualize: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| bool False | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Whether to publish the polygon in a separate topic. | ||
|
|
||
| :``<polygon_name>``.polygon_pub_topic: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string <polygon_name> | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Topic name to publish a polygon to. Used only if ``visualize`` is true. | ||
|
|
||
|
|
||
|
|
||
| Observation sources parameters | ||
| ============================== | ||
|
|
||
| ``<source name>`` is the corresponding data source name ID selected for this type. | ||
|
|
||
| :``<source name>``.type: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string "scan" | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Type of polygon shape. Could be ``scan``, ``pointcloud`` or ``range``. | ||
|
|
||
| :``<source name>``.topic: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| string "scan" | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Topic to listen the source data from. | ||
|
|
||
| :``<source name>``.min_height: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double 0.05 | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Minimum height the PointCloud projection to 2D space started from. Applicable for ``pointcloud`` type. | ||
|
|
||
| :``<source name>``.max_height: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double 0.5 | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Maximum height the PointCloud projection to 2D space ended with. Applicable for ``pointcloud`` type. | ||
|
|
||
| :``<source name>``.obstacles_angle: | ||
|
|
||
| ============== ============================= | ||
| Type Default | ||
| -------------- ----------------------------- | ||
| double PI / 180 (1 degree) | ||
| ============== ============================= | ||
|
|
||
| Description: | ||
| Angle increment (in radians) between nearby obstacle points at the range arc. Two outermost points from the field of view are not taken into account (they will always exist regardless of this value). Applicable for ``range`` type. | ||
|
|
||
|
|
||
| Example | ||
| ******* | ||
|
|
||
| Here is an example of configuration YAML for the Collision Detector. | ||
|
|
||
| .. code-block:: yaml | ||
|
|
||
| collision_detector: | ||
| ros__parameters: | ||
| base_frame_id: "base_footprint" | ||
| odom_frame_id: "odom" | ||
| transform_tolerance: 0.5 | ||
| source_timeout: 5.0 | ||
| base_shift_correction: True | ||
| polygons: ["PolygonFront"] | ||
| PolygonFront: | ||
| type: "polygon" | ||
| points: [0.3, 0.3, 0.3, -0.3, 0.0, -0.3, 0.0, 0.3] | ||
| action_type: "none" | ||
| min_points: 4 | ||
| visualize: True | ||
| polygon_pub_topic: "polygon_front" | ||
| observation_sources: ["scan"] | ||
| scan: | ||
| type: "scan" | ||
| topic: "scan" | ||
| pointcloud: | ||
| type: "pointcloud" | ||
| topic: "/intel_realsense_r200_depth/points" | ||
| min_height: 0.1 | ||
| max_height: 0.5 | ||
|
|
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.