diff --git a/2021summerOfCode/Summer_2021_Student_Program.html b/2021summerOfCode/Summer_2021_Student_Program.html index 47c9d832b..340415a3c 100644 --- a/2021summerOfCode/Summer_2021_Student_Program.html +++ b/2021summerOfCode/Summer_2021_Student_Program.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/assisted_teleop.html b/2021summerOfCode/projects/assisted_teleop.html index 413525970..624e8103b 100644 --- a/2021summerOfCode/projects/assisted_teleop.html +++ b/2021summerOfCode/projects/assisted_teleop.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/create_configuration_assistant.html b/2021summerOfCode/projects/create_configuration_assistant.html index 99a1b1e46..d07499e64 100644 --- a/2021summerOfCode/projects/create_configuration_assistant.html +++ b/2021summerOfCode/projects/create_configuration_assistant.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/create_plugins.html b/2021summerOfCode/projects/create_plugins.html index 35f842ad1..663b98bbc 100644 --- a/2021summerOfCode/projects/create_plugins.html +++ b/2021summerOfCode/projects/create_plugins.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/dynamic.html b/2021summerOfCode/projects/dynamic.html index bcd748a9f..fbbd0cf0a 100644 --- a/2021summerOfCode/projects/dynamic.html +++ b/2021summerOfCode/projects/dynamic.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/grid_maps.html b/2021summerOfCode/projects/grid_maps.html index d58c4f804..5274b5fd1 100644 --- a/2021summerOfCode/projects/grid_maps.html +++ b/2021summerOfCode/projects/grid_maps.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/localization.html b/2021summerOfCode/projects/localization.html index 20a8d83fd..606994e2d 100644 --- a/2021summerOfCode/projects/localization.html +++ b/2021summerOfCode/projects/localization.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/multithreading.html b/2021summerOfCode/projects/multithreading.html index 261fcae6f..3ed5de931 100644 --- a/2021summerOfCode/projects/multithreading.html +++ b/2021summerOfCode/projects/multithreading.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/navigation_rebranding.html b/2021summerOfCode/projects/navigation_rebranding.html index 7073ddf3c..f9f98d905 100644 --- a/2021summerOfCode/projects/navigation_rebranding.html +++ b/2021summerOfCode/projects/navigation_rebranding.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/safety_node.html b/2021summerOfCode/projects/safety_node.html index fc1050f13..09f0ac201 100644 --- a/2021summerOfCode/projects/safety_node.html +++ b/2021summerOfCode/projects/safety_node.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/semantics.html b/2021summerOfCode/projects/semantics.html index 9063369ab..7153875fd 100644 --- a/2021summerOfCode/projects/semantics.html +++ b/2021summerOfCode/projects/semantics.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/spinners.html b/2021summerOfCode/projects/spinners.html index 92c98d118..d45c27824 100644 --- a/2021summerOfCode/projects/spinners.html +++ b/2021summerOfCode/projects/spinners.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/testing.html b/2021summerOfCode/projects/testing.html index 64dcd0368..11004e6c3 100644 --- a/2021summerOfCode/projects/testing.html +++ b/2021summerOfCode/projects/testing.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/2021summerOfCode/projects/twist_n_config.html b/2021summerOfCode/projects/twist_n_config.html index a6a02c8f7..e3696f3c2 100644 --- a/2021summerOfCode/projects/twist_n_config.html +++ b/2021summerOfCode/projects/twist_n_config.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/_sources/configuration/index.rst.txt b/_sources/configuration/index.rst.txt index 325970ace..2924b4603 100644 --- a/_sources/configuration/index.rst.txt +++ b/_sources/configuration/index.rst.txt @@ -31,4 +31,5 @@ the best navigation performance. packages/configuring-constrained-smoother.rst packages/configuring-velocity-smoother.rst packages/configuring-collision-monitor.rst + packages/configuring-collision-detector.rst packages/configuring-waypoint-follower.rst diff --git a/_sources/configuration/packages/collision_monitor/configuring-collision-detector-node.rst.txt b/_sources/configuration/packages/collision_monitor/configuring-collision-detector-node.rst.txt new file mode 100644 index 000000000..d3cae7633 --- /dev/null +++ b/_sources/configuration/packages/collision_monitor/configuring-collision-detector-node.rst.txt @@ -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 N/A + ============== ============================= + + Description: + List of zones to check for data points. Causes an error, if not specialized. + + +:observation_sources: + + ============== ============================= + Type Default + -------------- ----------------------------- + vector N/A + ============== ============================= + + Description: + List of data sources (laser scanners, pointclouds, etc...). Causes an error, if not specialized. + +Polygons parameters +=================== + +```` is the corresponding polygon name ID selected for this type. + +:````.type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string N/A + ============== ============================= + + Description: + Type of polygon shape. Available values are ``polygon``, ``circle``. Causes an error, if not specialized. + +:````.points: + + ============== ============================= + Type Default + -------------- ----------------------------- + vector 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_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. + +:````.radius: + + ============== ============================= + Type Default + -------------- ----------------------------- + double N/A + ============== ============================= + + Description: + Circle radius. Used for ``circle`` type. Causes an error, if not specialized. + +:````.action_type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string N/A + ============== ============================= + + Description: + Only ``none`` action type is supported (more options available for collision monitor) + +:````.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. + +:````.visualize: + + ============== ============================= + Type Default + -------------- ----------------------------- + bool False + ============== ============================= + + Description: + Whether to publish the polygon in a separate topic. + +:````.polygon_pub_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string + ============== ============================= + + Description: + Topic name to publish a polygon to. Used only if ``visualize`` is true. + + + +Observation sources parameters +============================== + +```` is the corresponding data source name ID selected for this type. + +:````.type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "scan" + ============== ============================= + + Description: + Type of polygon shape. Could be ``scan``, ``pointcloud`` or ``range``. + +:````.topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "scan" + ============== ============================= + + Description: + Topic to listen the source data from. + +:````.min_height: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.05 + ============== ============================= + + Description: + Minimum height the PointCloud projection to 2D space started from. Applicable for ``pointcloud`` type. + +:````.max_height: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.5 + ============== ============================= + + Description: + Maximum height the PointCloud projection to 2D space ended with. Applicable for ``pointcloud`` type. + +:````.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 + diff --git a/_sources/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst.txt b/_sources/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst.txt new file mode 100644 index 000000000..a9b325a18 --- /dev/null +++ b/_sources/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst.txt @@ -0,0 +1,454 @@ +.. _configuring_collision_monitor_node: + +Collision Monitor Node +###################### + +The Collision Monitor is a node providing an additional level of robot safety. +It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level. + +This is analogous to safety sensor and hardware features; take in laser scans from a real-time certified safety scanner, detect if there is to be an imminent collision in a configurable bounding box, and either emergency-stop the certified robot controller or slow the robot to avoid such collision. +However, this node is done at the CPU level with any form of sensor. +As such, this does not provide hard real-time safety certifications, but uses the same types of techniques with the same types of data for users that do not have safety-rated laser sensors, safety-rated controllers, or wish to use any type of data input (e.g. pointclouds from depth or stereo or range sensors). + +This is a useful and integral part of large heavy industrial robots, or robots moving with high velocities, around people or other dynamic agents (e.g. other robots) as a safety mechanism for high-response emergency stopping. +The costmaps / trajectory planners will handle most situations, but this is to handle obstacles that virtually appear out of no where (from the robot's perspective) or approach the robot at such high speed it needs to immediately stop to prevent collision. + +See the package's ``README`` for more complete information. For more information how to bring-up your own Collision Monitor node, please refer to the :ref:`collision_monitor_tutorial` tutorial. + +Features +******** + +The Collision Monitor uses polygons relative the robot's base frame origin to define "zones". +Data that fall into these zones trigger an operation depending on the model being used. +A given instance of the Collision Monitor can have many zones with different models at the same time. +When multiple zones trigger at once, the most aggressive one is used (e.g. stop > slow 50% > slow 10%). + +The following models of safety behaviors are employed by Collision Monitor: + +- **Stop model**: Define a zone and a point threshold. If ``min_points`` or more obstacle points appear inside this area, stop the robot until the obstacles will disappear. +- **Slowdown model**: Define a zone around the robot and slow the maximum speed for a ``slowdown_ratio``, if ``min_points`` or more points will appear inside the area. +- **Limit model**: Define a zone around the robot and restricts the maximum linear and angular velocities to ``linear_limit`` and ``angular_limit`` values accordingly, if ``min_points`` or more points will appear inside the area. +- **Approach model**: Using the current robot speed, estimate the time to collision to sensor data. If the time is less than ``time_before_collision`` seconds (0.5, 2, 5, etc...), the robot will slow such that it is now at least ``time_before_collision`` seconds to collision. The effect here would be to keep the robot always ``time_before_collision`` seconds from any collision. + +The zones around the robot can take the following shapes: + +- Arbitrary user-defined polygon relative to the robot base frame, which can be static in a configuration file or dynamically changing via a topic interface. +- Robot footprint polygon, which is used in the approach behavior model only. Will use the static user-defined polygon or the footprint topic to allow it to be dynamically adjusted over time. +- Circle: is made for the best performance and could be used in the cases where the zone or robot footprint could be approximated by round shape. + +All shapes (``Polygon`` and ``Circle``) are derived from base ``Polygon`` class, so without loss of generality they would be called as "polygons". +Subscribed footprint is also having the same properties as other polygons, but it is being obtained a footprint topic for the Approach Model. + +The data may be obtained from different data sources: + +- Laser scanners (``sensor_msgs::msg::LaserScan`` messages) +- PointClouds (``sensor_msgs::msg::PointCloud2`` messages) +- IR/Sonars (``sensor_msgs::msg::Range`` messages) + +Parameters +********** + +: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. + +:cmd_vel_in_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "cmd_vel_raw" + ============== ============================= + + Description: + Input ``cmd_vel`` topic with desired robot velocity. + +:cmd_vel_out_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "cmd_vel" + ============== ============================= + + Description: + Output ``cmd_vel`` topic with output produced by Collision Monitor velocities. + +:state_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "" + ============== ============================= + + Description: + Output the currently activated polygon action type and name. Optional parameter. No publisher will be created if it is unspecified. + +: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). + +:stop_pub_timeout: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 1.0 + ============== ============================= + + Description: + Timeout, after which zero-velocity ceases to be published. It could be used for other overrode systems outside Nav2 are trying to bring the robot out of a state close to a collision, or to allow a standing robot to go into sleep mode. + +:polygons: + + ============== ============================= + Type Default + -------------- ----------------------------- + vector N/A + ============== ============================= + + Description: + List of zones (stop/slowdown/limit bounding boxes, footprint, approach circle, etc...). Causes an error, if not specialized. + + +:observation_sources: + + ============== ============================= + Type Default + -------------- ----------------------------- + vector N/A + ============== ============================= + + Description: + List of data sources (laser scanners, pointclouds, etc...). Causes an error, if not specialized. + +Polygons parameters +=================== + +```` is the corresponding polygon name ID selected for this type. + +:````.type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string N/A + ============== ============================= + + Description: + Type of polygon shape. Available values are ``polygon``, ``circle``. Causes an error, if not specialized. + +:````.points: + + ============== ============================= + Type Default + -------------- ----------------------------- + vector 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 monitor will use dynamic polygon subscription to ``polygon_sub_topic`` for points in the ``stop``/``slowdown``/``limit`` action types, or footprint subscriber to ``footprint_topic`` for ``approach`` action type. + +:````.polygon_sub_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string N/A + ============== ============================= + + Description: + Topic to listen the polygon points from. Applicable only for ``polygon`` type and ``stop``/``slowdown``/``limit`` action types. 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. + +:````.footprint_topic: + + ============== =================================== + Type Default + -------------- ----------------------------------- + string "local_costmap/published_footprint" + ============== =================================== + + Description: + Topic to listen the robot footprint from. Applicable only for ``polygon`` type and ``approach`` action type. If both ``points`` and ``footprint_topic`` are specified, the static ``points`` takes priority. + +:````.radius: + + ============== ============================= + Type Default + -------------- ----------------------------- + double N/A + ============== ============================= + + Description: + Circle radius. Used for ``circle`` type. Causes an error, if not specialized. + +:````.action_type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string N/A + ============== ============================= + + Description: + Zone behavior model. Available values are ``stop``, ``slowdown``, ``limit``, ``approach``. Causes an error, if not specialized. + +:````.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. + +:````.slowdown_ratio: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.5 + ============== ============================= + + Description: + Robot slowdown (share of its actual speed). Applicable for ``slowdown`` action type. + +:````.linear_limit: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.5 + ============== ============================= + + Description: + Robot linear speed limit. Applicable for ``limit`` action type. + +:````.angular_limit: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.5 + ============== ============================= + + Description: + Robot angular speed limit. Applicable for ``limit`` action type. + +:````.time_before_collision: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 2.0 + ============== ============================= + + Description: + Time before collision in seconds. Maximum simulation time used in collision prediction. Higher values mean lower performance. Applicable for ``approach`` action type. + +:````.simulation_time_step: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.1 + ============== ============================= + + Description: + Time iteration step for robot movement simulation during collision prediction. Higher values mean lower prediction accuracy but better performance. Applicable for ``approach`` action type. + +:````.visualize: + + ============== ============================= + Type Default + -------------- ----------------------------- + bool False + ============== ============================= + + Description: + Whether to publish the polygon in a separate topic. + +:````.polygon_pub_topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string + ============== ============================= + + Description: + Topic name to publish a polygon to. Used only if ``visualize`` is true. + + + +Observation sources parameters +============================== + +```` is the corresponding data source name ID selected for this type. + +:````.type: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "scan" + ============== ============================= + + Description: + Type of polygon shape. Could be ``scan``, ``pointcloud`` or ``range``. + +:````.topic: + + ============== ============================= + Type Default + -------------- ----------------------------- + string "scan" + ============== ============================= + + Description: + Topic to listen the source data from. + +:````.min_height: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.05 + ============== ============================= + + Description: + Minimum height the PointCloud projection to 2D space started from. Applicable for ``pointcloud`` type. + +:````.max_height: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 0.5 + ============== ============================= + + Description: + Maximum height the PointCloud projection to 2D space ended with. Applicable for ``pointcloud`` type. + +:````.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 Monitor. + +.. code-block:: yaml + + collision_monitor: + ros__parameters: + base_frame_id: "base_footprint" + odom_frame_id: "odom" + cmd_vel_in_topic: "cmd_vel_raw" + cmd_vel_out_topic: "cmd_vel" + state_topic: "collision_monitor_state" + transform_tolerance: 0.5 + source_timeout: 5.0 + base_shift_correction: True + stop_pub_timeout: 2.0 + polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"] + PolygonStop: + type: "circle" + radius: 0.3 + action_type: "stop" + min_points: 4 # max_points: 3 for Humble + visualize: True + polygon_pub_topic: "polygon_stop" + PolygonSlow: + type: "polygon" + points: [1.0, 1.0, 1.0, -1.0, -0.5, -1.0, -0.5, 1.0] + action_type: "slowdown" + min_points: 4 # max_points: 3 for Humble + slowdown_ratio: 0.3 + visualize: True + polygon_pub_topic: "polygon_slowdown" + PolygonLimit: + type: "polygon" + points: [0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5] + action_type: "limit" + min_points: 4 # max_points: 3 for Humble + linear_limit: 0.4 + angular_limit: 0.5 + visualize: True + polygon_pub_topic: "polygon_limit" + FootprintApproach: + type: "polygon" + action_type: "approach" + footprint_topic: "/local_costmap/published_footprint" + time_before_collision: 2.0 + simulation_time_step: 0.02 + min_points: 6 # max_points: 5 for Humble + visualize: False + observation_sources: ["scan", "pointcloud"] + scan: + type: "scan" + topic: "/scan" + pointcloud: + type: "pointcloud" + topic: "/intel_realsense_r200_depth/points" + min_height: 0.1 + max_height: 0.5 diff --git a/_sources/configuration/packages/configuring-collision-monitor.rst.txt b/_sources/configuration/packages/configuring-collision-monitor.rst.txt index 4a8f66d9f..3caed6033 100644 --- a/_sources/configuration/packages/configuring-collision-monitor.rst.txt +++ b/_sources/configuration/packages/configuring-collision-monitor.rst.txt @@ -3,453 +3,21 @@ Collision Monitor ################# -The Collision Monitor is a node providing an additional level of robot safety. -It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level. +Source code and ``README`` with design, explanations, and metrics can be found on Github_. -This is analogous to safety sensor and hardware features; take in laser scans from a real-time certified safety scanner, detect if there is to be an imminent collision in a configurable bounding box, and either emergency-stop the certified robot controller or slow the robot to avoid such collision. -However, this node is done at the CPU level with any form of sensor. -As such, this does not provide hard real-time safety certifications, but uses the same types of techniques with the same types of data for users that do not have safety-rated laser sensors, safety-rated controllers, or wish to use any type of data input (e.g. pointclouds from depth or stereo or range sensors). +.. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_collision_monitor -This is a useful and integral part of large heavy industrial robots, or robots moving with high velocities, around people or other dynamic agents (e.g. other robots) as a safety mechanism for high-response emergency stopping. -The costmaps / trajectory planners will handle most situations, but this is to handle obstacles that virtually appear out of no where (from the robot's perspective) or approach the robot at such high speed it needs to immediately stop to prevent collision. +The ``nav2_collision_monitor`` package contains nodes providing an additional level of robot safety, namely the Collision Monitor and the Collision Detector. +The Collision Monitor is a node providing an additional level of robot safety. It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level. +The Collision Detector 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 a message to a topic. -See the package's ``README`` for more complete information. +Provided Nodes +**************** +The nodes listed below are inside the ``nav2_collision_monitor`` package. See the pages for individual configuration information. -Features -******** +.. toctree:: + :maxdepth: 1 -The Collision Monitor uses polygons relative the robot's base frame origin to define "zones". -Data that fall into these zones trigger an operation depending on the model being used. -A given instance of the Collision Monitor can have many zones with different models at the same time. -When multiple zones trigger at once, the most aggressive one is used (e.g. stop > slow 50% > slow 10%). + collision_monitor/configuring-collision-monitor-node.rst + collision_monitor/configuring-collision-detector-node.rst -The following models of safety behaviors are employed by Collision Monitor: - -- **Stop model**: Define a zone and a point threshold. If ``min_points`` or more obstacle points appear inside this area, stop the robot until the obstacles will disappear. -- **Slowdown model**: Define a zone around the robot and slow the maximum speed for a ``slowdown_ratio``, if ``min_points`` or more points will appear inside the area. -- **Limit model**: Define a zone around the robot and restricts the maximum linear and angular velocities to ``linear_limit`` and ``angular_limit`` values accordingly, if ``min_points`` or more points will appear inside the area. -- **Approach model**: Using the current robot speed, estimate the time to collision to sensor data. If the time is less than ``time_before_collision`` seconds (0.5, 2, 5, etc...), the robot will slow such that it is now at least ``time_before_collision`` seconds to collision. The effect here would be to keep the robot always ``time_before_collision`` seconds from any collision. - -The zones around the robot can take the following shapes: - -- Arbitrary user-defined polygon relative to the robot base frame, which can be static in a configuration file or dynamically changing via a topic interface. -- Robot footprint polygon, which is used in the approach behavior model only. Will use the static user-defined polygon or the footprint topic to allow it to be dynamically adjusted over time. -- Circle: is made for the best performance and could be used in the cases where the zone or robot footprint could be approximated by round shape. - -All shapes (``Polygon`` and ``Circle``) are derived from base ``Polygon`` class, so without loss of generality they would be called as "polygons". -Subscribed footprint is also having the same properties as other polygons, but it is being obtained a footprint topic for the Approach Model. - -The data may be obtained from different data sources: - -- Laser scanners (``sensor_msgs::msg::LaserScan`` messages) -- PointClouds (``sensor_msgs::msg::PointCloud2`` messages) -- IR/Sonars (``sensor_msgs::msg::Range`` messages) - -Parameters -********** - -: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. - -:cmd_vel_in_topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string "cmd_vel_raw" - ============== ============================= - - Description: - Input ``cmd_vel`` topic with desired robot velocity. - -:cmd_vel_out_topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string "cmd_vel" - ============== ============================= - - Description: - Output ``cmd_vel`` topic with output produced by Collision Monitor velocities. - -:state_topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string "" - ============== ============================= - - Description: - Output the currently activated polygon action type and name. Optional parameter. No publisher will be created if it is unspecified. - -: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). - -:stop_pub_timeout: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 1.0 - ============== ============================= - - Description: - Timeout, after which zero-velocity ceases to be published. It could be used for other overrode systems outside Nav2 are trying to bring the robot out of a state close to a collision, or to allow a standing robot to go into sleep mode. - -:polygons: - - ============== ============================= - Type Default - -------------- ----------------------------- - vector N/A - ============== ============================= - - Description: - List of zones (stop/slowdown/limit bounding boxes, footprint, approach circle, etc...). Causes an error, if not specialized. - - -:observation_sources: - - ============== ============================= - Type Default - -------------- ----------------------------- - vector N/A - ============== ============================= - - Description: - List of data sources (laser scanners, pointclouds, etc...). Causes an error, if not specialized. - -Polygons parameters -=================== - -```` is the corresponding polygon name ID selected for this type. - -:````.type: - - ============== ============================= - Type Default - -------------- ----------------------------- - string N/A - ============== ============================= - - Description: - Type of polygon shape. Available values are ``polygon``, ``circle``. Causes an error, if not specialized. - -:````.points: - - ============== ============================= - Type Default - -------------- ----------------------------- - vector 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 monitor will use dynamic polygon subscription to ``polygon_sub_topic`` for points in the ``stop``/``slowdown``/``limit`` action types, or footprint subscriber to ``footprint_topic`` for ``approach`` action type. - -:````.polygon_sub_topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string N/A - ============== ============================= - - Description: - Topic to listen the polygon points from. Applicable only for ``polygon`` type and ``stop``/``slowdown``/``limit`` action types. 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. - -:````.footprint_topic: - - ============== =================================== - Type Default - -------------- ----------------------------------- - string "local_costmap/published_footprint" - ============== =================================== - - Description: - Topic to listen the robot footprint from. Applicable only for ``polygon`` type and ``approach`` action type. If both ``points`` and ``footprint_topic`` are specified, the static ``points`` takes priority. - -:````.radius: - - ============== ============================= - Type Default - -------------- ----------------------------- - double N/A - ============== ============================= - - Description: - Circle radius. Used for ``circle`` type. Causes an error, if not specialized. - -:````.action_type: - - ============== ============================= - Type Default - -------------- ----------------------------- - string N/A - ============== ============================= - - Description: - Zone behavior model. Available values are ``stop``, ``slowdown``, ``limit``, ``approach``. Causes an error, if not specialized. - -:````.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. - -:````.slowdown_ratio: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.5 - ============== ============================= - - Description: - Robot slowdown (share of its actual speed). Applicable for ``slowdown`` action type. - -:````.linear_limit: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.5 - ============== ============================= - - Description: - Robot linear speed limit. Applicable for ``limit`` action type. - -:````.angular_limit: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.5 - ============== ============================= - - Description: - Robot angular speed limit. Applicable for ``limit`` action type. - -:````.time_before_collision: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 2.0 - ============== ============================= - - Description: - Time before collision in seconds. Maximum simulation time used in collision prediction. Higher values mean lower performance. Applicable for ``approach`` action type. - -:````.simulation_time_step: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.1 - ============== ============================= - - Description: - Time iteration step for robot movement simulation during collision prediction. Higher values mean lower prediction accuracy but better performance. Applicable for ``approach`` action type. - -:````.visualize: - - ============== ============================= - Type Default - -------------- ----------------------------- - bool False - ============== ============================= - - Description: - Whether to publish the polygon in a separate topic. - -:````.polygon_pub_topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string - ============== ============================= - - Description: - Topic name to publish a polygon to. Used only if ``visualize`` is true. - - - -Observation sources parameters -============================== - -```` is the corresponding data source name ID selected for this type. - -:````.type: - - ============== ============================= - Type Default - -------------- ----------------------------- - string "scan" - ============== ============================= - - Description: - Type of polygon shape. Could be ``scan``, ``pointcloud`` or ``range``. - -:````.topic: - - ============== ============================= - Type Default - -------------- ----------------------------- - string "scan" - ============== ============================= - - Description: - Topic to listen the source data from. - -:````.min_height: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.05 - ============== ============================= - - Description: - Minimum height the PointCloud projection to 2D space started from. Applicable for ``pointcloud`` type. - -:````.max_height: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 0.5 - ============== ============================= - - Description: - Maximum height the PointCloud projection to 2D space ended with. Applicable for ``pointcloud`` type. - -:````.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 Monitor. -For more information how to bring-up your own Collision Monitor node, please refer to the :ref:`collision_monitor_tutorial` tutorial. - -.. code-block:: yaml - - collision_monitor: - ros__parameters: - base_frame_id: "base_footprint" - odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_raw" - cmd_vel_out_topic: "cmd_vel" - state_topic: "collision_monitor_state" - transform_tolerance: 0.5 - source_timeout: 5.0 - base_shift_correction: True - stop_pub_timeout: 2.0 - polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"] - PolygonStop: - type: "circle" - radius: 0.3 - action_type: "stop" - min_points: 4 # max_points: 3 for Humble - visualize: True - polygon_pub_topic: "polygon_stop" - PolygonSlow: - type: "polygon" - points: [1.0, 1.0, 1.0, -1.0, -0.5, -1.0, -0.5, 1.0] - action_type: "slowdown" - min_points: 4 # max_points: 3 for Humble - slowdown_ratio: 0.3 - visualize: True - polygon_pub_topic: "polygon_slowdown" - PolygonLimit: - type: "polygon" - points: [0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5] - action_type: "limit" - min_points: 4 # max_points: 3 for Humble - linear_limit: 0.4 - angular_limit: 0.5 - visualize: True - polygon_pub_topic: "polygon_limit" - FootprintApproach: - type: "polygon" - action_type: "approach" - footprint_topic: "/local_costmap/published_footprint" - time_before_collision: 2.0 - simulation_time_step: 0.02 - min_points: 6 # max_points: 5 for Humble - visualize: False - observation_sources: ["scan", "pointcloud"] - scan: - type: "scan" - topic: "/scan" - pointcloud: - type: "pointcloud" - topic: "/intel_realsense_r200_depth/points" - min_height: 0.1 - max_height: 0.5 diff --git a/_sources/migration/Iron.rst.txt b/_sources/migration/Iron.rst.txt index 78974fe90..1195c53f7 100644 --- a/_sources/migration/Iron.rst.txt +++ b/_sources/migration/Iron.rst.txt @@ -66,3 +66,9 @@ Smac Planner Debug Param Name Change ************************************ ``debug_visualizations`` replaces ``viz_expansions`` parameter in Hybrid-A* to reflect the new inclusion of footprint debug information being published as well. + +New node in nav2_collision_monitor: Collision Detector +****************************************************** + +In this `PR #3693 `_ A new node was introduced in the nav2_collision_monitor: Collision Detector. +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 that might be used by any external module (e.g. switching LED or sound alarm in case of collision). diff --git a/about/index.html b/about/index.html index f899188e7..b3ae1bd1e 100644 --- a/about/index.html +++ b/about/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/about/related_projects.html b/about/related_projects.html index 771e73d1e..52ea91ae1 100644 --- a/about/related_projects.html +++ b/about/related_projects.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/about/robots.html b/about/robots.html index 936d06365..547fc18f2 100644 --- a/about/robots.html +++ b/about/robots.html @@ -688,13 +688,11 @@
  • Collision Monitor diff --git a/about/ros1_comparison.html b/about/ros1_comparison.html index 50959f8bb..74796cc4b 100644 --- a/about/ros1_comparison.html +++ b/about/ros1_comparison.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/index.html b/behavior_trees/index.html index d3c2f9536..7f06233e4 100644 --- a/behavior_trees/index.html +++ b/behavior_trees/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/overview/detailed_behavior_tree_walkthrough.html b/behavior_trees/overview/detailed_behavior_tree_walkthrough.html index 636f7e817..2fb9bb540 100644 --- a/behavior_trees/overview/detailed_behavior_tree_walkthrough.html +++ b/behavior_trees/overview/detailed_behavior_tree_walkthrough.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/overview/nav2_specific_nodes.html b/behavior_trees/overview/nav2_specific_nodes.html index 14274f14e..7127730f8 100644 --- a/behavior_trees/overview/nav2_specific_nodes.html +++ b/behavior_trees/overview/nav2_specific_nodes.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/follow_point.html b/behavior_trees/trees/follow_point.html index ff77d395a..42d8d694e 100644 --- a/behavior_trees/trees/follow_point.html +++ b/behavior_trees/trees/follow_point.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/nav_through_poses_recovery.html b/behavior_trees/trees/nav_through_poses_recovery.html index 36b014767..09f6cb7ed 100644 --- a/behavior_trees/trees/nav_through_poses_recovery.html +++ b/behavior_trees/trees/nav_through_poses_recovery.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.html b/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.html index feb803fa3..a46964c69 100644 --- a/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.html +++ b/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/nav_to_pose_recovery.html b/behavior_trees/trees/nav_to_pose_recovery.html index e9112f813..39f6c527c 100644 --- a/behavior_trees/trees/nav_to_pose_recovery.html +++ b/behavior_trees/trees/nav_to_pose_recovery.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.html b/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.html index eaace8967..136e0ef1c 100644 --- a/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.html +++ b/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/behavior_trees/trees/odometry_calibration.html b/behavior_trees/trees/odometry_calibration.html index d5ee17843..b50eeb5bc 100644 --- a/behavior_trees/trees/odometry_calibration.html +++ b/behavior_trees/trees/odometry_calibration.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/commander_api/index.html b/commander_api/index.html index f3ae37b8e..8b8d60db9 100644 --- a/commander_api/index.html +++ b/commander_api/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/concepts/index.html b/concepts/index.html index 1143efd8d..b7bd6fcf5 100644 --- a/concepts/index.html +++ b/concepts/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/index.html b/configuration/index.html index f9aebd6db..0d7434d16 100644 --- a/configuration/index.html +++ b/configuration/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/AssistedTeleop.html b/configuration/packages/bt-plugins/actions/AssistedTeleop.html index 6bd398167..f0c20ba79 100644 --- a/configuration/packages/bt-plugins/actions/AssistedTeleop.html +++ b/configuration/packages/bt-plugins/actions/AssistedTeleop.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/BackUp.html b/configuration/packages/bt-plugins/actions/BackUp.html index 0685f7b37..14da37cc8 100644 --- a/configuration/packages/bt-plugins/actions/BackUp.html +++ b/configuration/packages/bt-plugins/actions/BackUp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelAssistedTeleop.html b/configuration/packages/bt-plugins/actions/CancelAssistedTeleop.html index be0a4898c..3d19683ac 100644 --- a/configuration/packages/bt-plugins/actions/CancelAssistedTeleop.html +++ b/configuration/packages/bt-plugins/actions/CancelAssistedTeleop.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelBackUp.html b/configuration/packages/bt-plugins/actions/CancelBackUp.html index 6a3a9dfe0..98413d0dd 100644 --- a/configuration/packages/bt-plugins/actions/CancelBackUp.html +++ b/configuration/packages/bt-plugins/actions/CancelBackUp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelControl.html b/configuration/packages/bt-plugins/actions/CancelControl.html index 1e6a585e6..da1cfed0b 100644 --- a/configuration/packages/bt-plugins/actions/CancelControl.html +++ b/configuration/packages/bt-plugins/actions/CancelControl.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelDriveOnHeading.html b/configuration/packages/bt-plugins/actions/CancelDriveOnHeading.html index 1ed55bae4..515aa6559 100644 --- a/configuration/packages/bt-plugins/actions/CancelDriveOnHeading.html +++ b/configuration/packages/bt-plugins/actions/CancelDriveOnHeading.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelSpin.html b/configuration/packages/bt-plugins/actions/CancelSpin.html index 1951eee8e..8761c8d86 100644 --- a/configuration/packages/bt-plugins/actions/CancelSpin.html +++ b/configuration/packages/bt-plugins/actions/CancelSpin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/CancelWait.html b/configuration/packages/bt-plugins/actions/CancelWait.html index bdc08322b..54a403b97 100644 --- a/configuration/packages/bt-plugins/actions/CancelWait.html +++ b/configuration/packages/bt-plugins/actions/CancelWait.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.html b/configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.html index 4f8cbb3ea..0a2bb8eaf 100644 --- a/configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.html +++ b/configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.html b/configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.html index 912d5678b..f5ed2ecd8 100644 --- a/configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.html +++ b/configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ClearEntireCostmap.html b/configuration/packages/bt-plugins/actions/ClearEntireCostmap.html index 89e9b65cc..73e2213f7 100644 --- a/configuration/packages/bt-plugins/actions/ClearEntireCostmap.html +++ b/configuration/packages/bt-plugins/actions/ClearEntireCostmap.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.html b/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.html index 66f911598..06d285f7d 100644 --- a/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.html +++ b/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ComputePathToPose.html b/configuration/packages/bt-plugins/actions/ComputePathToPose.html index cca8e0f38..8056939d9 100644 --- a/configuration/packages/bt-plugins/actions/ComputePathToPose.html +++ b/configuration/packages/bt-plugins/actions/ComputePathToPose.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ControllerSelector.html b/configuration/packages/bt-plugins/actions/ControllerSelector.html index bb8c3d18b..757a5faec 100644 --- a/configuration/packages/bt-plugins/actions/ControllerSelector.html +++ b/configuration/packages/bt-plugins/actions/ControllerSelector.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/DriveOnHeading.html b/configuration/packages/bt-plugins/actions/DriveOnHeading.html index 6bf4726a3..aad5b7c08 100644 --- a/configuration/packages/bt-plugins/actions/DriveOnHeading.html +++ b/configuration/packages/bt-plugins/actions/DriveOnHeading.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/FollowPath.html b/configuration/packages/bt-plugins/actions/FollowPath.html index 7a0033a7c..db0ea7ac5 100644 --- a/configuration/packages/bt-plugins/actions/FollowPath.html +++ b/configuration/packages/bt-plugins/actions/FollowPath.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/GoalCheckerSelector.html b/configuration/packages/bt-plugins/actions/GoalCheckerSelector.html index 9ce5f77d3..3b41a00d0 100644 --- a/configuration/packages/bt-plugins/actions/GoalCheckerSelector.html +++ b/configuration/packages/bt-plugins/actions/GoalCheckerSelector.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/NavigateThroughPoses.html b/configuration/packages/bt-plugins/actions/NavigateThroughPoses.html index df108e3ef..9764777db 100644 --- a/configuration/packages/bt-plugins/actions/NavigateThroughPoses.html +++ b/configuration/packages/bt-plugins/actions/NavigateThroughPoses.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/NavigateToPose.html b/configuration/packages/bt-plugins/actions/NavigateToPose.html index cec03d306..d288bf1c1 100644 --- a/configuration/packages/bt-plugins/actions/NavigateToPose.html +++ b/configuration/packages/bt-plugins/actions/NavigateToPose.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/PlannerSelector.html b/configuration/packages/bt-plugins/actions/PlannerSelector.html index e71e3a7fd..c71dcaac3 100644 --- a/configuration/packages/bt-plugins/actions/PlannerSelector.html +++ b/configuration/packages/bt-plugins/actions/PlannerSelector.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.html b/configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.html index ac91d1a9b..9a1817e11 100644 --- a/configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.html +++ b/configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/RemovePassedGoals.html b/configuration/packages/bt-plugins/actions/RemovePassedGoals.html index 96e30a4b9..b1375b20b 100644 --- a/configuration/packages/bt-plugins/actions/RemovePassedGoals.html +++ b/configuration/packages/bt-plugins/actions/RemovePassedGoals.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/Smooth.html b/configuration/packages/bt-plugins/actions/Smooth.html index 35e9e9594..c533bcea5 100644 --- a/configuration/packages/bt-plugins/actions/Smooth.html +++ b/configuration/packages/bt-plugins/actions/Smooth.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/SmootherSelector.html b/configuration/packages/bt-plugins/actions/SmootherSelector.html index 3b73761dc..1534348dd 100644 --- a/configuration/packages/bt-plugins/actions/SmootherSelector.html +++ b/configuration/packages/bt-plugins/actions/SmootherSelector.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/Spin.html b/configuration/packages/bt-plugins/actions/Spin.html index bf4e5f2e1..4395ee864 100644 --- a/configuration/packages/bt-plugins/actions/Spin.html +++ b/configuration/packages/bt-plugins/actions/Spin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/TruncatePath.html b/configuration/packages/bt-plugins/actions/TruncatePath.html index ab0565322..5e99b58cc 100644 --- a/configuration/packages/bt-plugins/actions/TruncatePath.html +++ b/configuration/packages/bt-plugins/actions/TruncatePath.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/TruncatePathLocal.html b/configuration/packages/bt-plugins/actions/TruncatePathLocal.html index 0e527cd06..39643eccc 100644 --- a/configuration/packages/bt-plugins/actions/TruncatePathLocal.html +++ b/configuration/packages/bt-plugins/actions/TruncatePathLocal.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/actions/Wait.html b/configuration/packages/bt-plugins/actions/Wait.html index 4db8a299e..16f63b511 100644 --- a/configuration/packages/bt-plugins/actions/Wait.html +++ b/configuration/packages/bt-plugins/actions/Wait.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.html b/configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.html index b5b780af3..24374d8bf 100644 --- a/configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.html +++ b/configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/DistanceTraveled.html b/configuration/packages/bt-plugins/conditions/DistanceTraveled.html index 32912de39..4160df357 100644 --- a/configuration/packages/bt-plugins/conditions/DistanceTraveled.html +++ b/configuration/packages/bt-plugins/conditions/DistanceTraveled.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.html b/configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.html index 575c06c27..c1fe11313 100644 --- a/configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.html +++ b/configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/GoalReached.html b/configuration/packages/bt-plugins/conditions/GoalReached.html index 961c7afb8..57836b9a0 100644 --- a/configuration/packages/bt-plugins/conditions/GoalReached.html +++ b/configuration/packages/bt-plugins/conditions/GoalReached.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/GoalUpdated.html b/configuration/packages/bt-plugins/conditions/GoalUpdated.html index 199501133..6c66f24d9 100644 --- a/configuration/packages/bt-plugins/conditions/GoalUpdated.html +++ b/configuration/packages/bt-plugins/conditions/GoalUpdated.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/InitialPoseReceived.html b/configuration/packages/bt-plugins/conditions/InitialPoseReceived.html index 0816ad15b..7d9daab1a 100644 --- a/configuration/packages/bt-plugins/conditions/InitialPoseReceived.html +++ b/configuration/packages/bt-plugins/conditions/InitialPoseReceived.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/IsBatteryCharging.html b/configuration/packages/bt-plugins/conditions/IsBatteryCharging.html index 81b816083..7fa9369d8 100644 --- a/configuration/packages/bt-plugins/conditions/IsBatteryCharging.html +++ b/configuration/packages/bt-plugins/conditions/IsBatteryCharging.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/IsBatteryLow.html b/configuration/packages/bt-plugins/conditions/IsBatteryLow.html index 779c01a1e..cbe93aa3b 100644 --- a/configuration/packages/bt-plugins/conditions/IsBatteryLow.html +++ b/configuration/packages/bt-plugins/conditions/IsBatteryLow.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/IsPathValid.html b/configuration/packages/bt-plugins/conditions/IsPathValid.html index c10a08b1d..2f663faf9 100644 --- a/configuration/packages/bt-plugins/conditions/IsPathValid.html +++ b/configuration/packages/bt-plugins/conditions/IsPathValid.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/IsStuck.html b/configuration/packages/bt-plugins/conditions/IsStuck.html index b27969ec9..8d9c0a468 100644 --- a/configuration/packages/bt-plugins/conditions/IsStuck.html +++ b/configuration/packages/bt-plugins/conditions/IsStuck.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/PathExpiringTimer.html b/configuration/packages/bt-plugins/conditions/PathExpiringTimer.html index 51f5f0a54..43a1b031a 100644 --- a/configuration/packages/bt-plugins/conditions/PathExpiringTimer.html +++ b/configuration/packages/bt-plugins/conditions/PathExpiringTimer.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/TimeExpired.html b/configuration/packages/bt-plugins/conditions/TimeExpired.html index 528952eae..5edeb537f 100644 --- a/configuration/packages/bt-plugins/conditions/TimeExpired.html +++ b/configuration/packages/bt-plugins/conditions/TimeExpired.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/TransformAvailable.html b/configuration/packages/bt-plugins/conditions/TransformAvailable.html index 79ab69615..5644b8583 100644 --- a/configuration/packages/bt-plugins/conditions/TransformAvailable.html +++ b/configuration/packages/bt-plugins/conditions/TransformAvailable.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.html b/configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.html index fd9c9a0d7..b438384e1 100644 --- a/configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.html +++ b/configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.html b/configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.html index 9753daae4..982162b83 100644 --- a/configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.html +++ b/configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.html b/configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.html index d49c5a2a5..c3448ed49 100644 --- a/configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.html +++ b/configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/controls/PipelineSequence.html b/configuration/packages/bt-plugins/controls/PipelineSequence.html index d8e702a71..ae9bb974d 100644 --- a/configuration/packages/bt-plugins/controls/PipelineSequence.html +++ b/configuration/packages/bt-plugins/controls/PipelineSequence.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/controls/RecoveryNode.html b/configuration/packages/bt-plugins/controls/RecoveryNode.html index 8bc51de62..d93f36e58 100644 --- a/configuration/packages/bt-plugins/controls/RecoveryNode.html +++ b/configuration/packages/bt-plugins/controls/RecoveryNode.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/controls/RoundRobin.html b/configuration/packages/bt-plugins/controls/RoundRobin.html index c30e5eb11..aec9955fe 100644 --- a/configuration/packages/bt-plugins/controls/RoundRobin.html +++ b/configuration/packages/bt-plugins/controls/RoundRobin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/DistanceController.html b/configuration/packages/bt-plugins/decorators/DistanceController.html index 2e23fc419..a21827dc0 100644 --- a/configuration/packages/bt-plugins/decorators/DistanceController.html +++ b/configuration/packages/bt-plugins/decorators/DistanceController.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/GoalUpdater.html b/configuration/packages/bt-plugins/decorators/GoalUpdater.html index 70b96c57f..9683a6bb3 100644 --- a/configuration/packages/bt-plugins/decorators/GoalUpdater.html +++ b/configuration/packages/bt-plugins/decorators/GoalUpdater.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/PathLongerOnApproach.html b/configuration/packages/bt-plugins/decorators/PathLongerOnApproach.html index bc26d411e..4c9a416d0 100644 --- a/configuration/packages/bt-plugins/decorators/PathLongerOnApproach.html +++ b/configuration/packages/bt-plugins/decorators/PathLongerOnApproach.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/RateController.html b/configuration/packages/bt-plugins/decorators/RateController.html index fc16b8a92..580181ce5 100644 --- a/configuration/packages/bt-plugins/decorators/RateController.html +++ b/configuration/packages/bt-plugins/decorators/RateController.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/SingleTrigger.html b/configuration/packages/bt-plugins/decorators/SingleTrigger.html index 2a7d747ab..dab3bff28 100644 --- a/configuration/packages/bt-plugins/decorators/SingleTrigger.html +++ b/configuration/packages/bt-plugins/decorators/SingleTrigger.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/bt-plugins/decorators/SpeedController.html b/configuration/packages/bt-plugins/decorators/SpeedController.html index 845628e9f..3028e18d6 100644 --- a/configuration/packages/bt-plugins/decorators/SpeedController.html +++ b/configuration/packages/bt-plugins/decorators/SpeedController.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/collision_monitor/configuring-collision-detector-node.html b/configuration/packages/collision_monitor/configuring-collision-detector-node.html new file mode 100644 index 000000000..ebbb80fee --- /dev/null +++ b/configuration/packages/collision_monitor/configuring-collision-detector-node.html @@ -0,0 +1,1481 @@ + + + + + + Collision Detector Node — Navigation 2 1.0.0 documentation + + + + + + + + + + + + + + + + + + + + + + + +
    + + +
    + +
    + + + Edit + + + +
    +
    + +
    +
    +
    +
    + +
    +

    Collision Detector Node

    +

    The Collision Detector is a node similar to the Collision Monitor, so it is recommended to read the Using Collision Monitor 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.

    +
    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
    +
    +
    +
    +
    + + +
    +
    +
    + +
    + +
    +

    © Copyright 2020.

    +
    + + + +
    +
    + + +
    +
    +
    + + + + + + + + + + + + \ No newline at end of file diff --git a/configuration/packages/collision_monitor/configuring-collision-monitor-node.html b/configuration/packages/collision_monitor/configuring-collision-monitor-node.html new file mode 100644 index 000000000..4c51fddf9 --- /dev/null +++ b/configuration/packages/collision_monitor/configuring-collision-monitor-node.html @@ -0,0 +1,1715 @@ + + + + + + Collision Monitor Node — Navigation 2 1.0.0 documentation + + + + + + + + + + + + + + + + + + + + + + + +
    + + +
    + +
    + + + Edit + + + +
    +
    + +
    +
    +
    +
    + +
    +

    Collision Monitor Node

    +

    The Collision Monitor is a node providing an additional level of robot safety. +It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level.

    +

    This is analogous to safety sensor and hardware features; take in laser scans from a real-time certified safety scanner, detect if there is to be an imminent collision in a configurable bounding box, and either emergency-stop the certified robot controller or slow the robot to avoid such collision. +However, this node is done at the CPU level with any form of sensor. +As such, this does not provide hard real-time safety certifications, but uses the same types of techniques with the same types of data for users that do not have safety-rated laser sensors, safety-rated controllers, or wish to use any type of data input (e.g. pointclouds from depth or stereo or range sensors).

    +

    This is a useful and integral part of large heavy industrial robots, or robots moving with high velocities, around people or other dynamic agents (e.g. other robots) as a safety mechanism for high-response emergency stopping. +The costmaps / trajectory planners will handle most situations, but this is to handle obstacles that virtually appear out of no where (from the robot’s perspective) or approach the robot at such high speed it needs to immediately stop to prevent collision.

    +

    See the package’s README for more complete information. For more information how to bring-up your own Collision Monitor node, please refer to the Using Collision Monitor tutorial.

    +
    +

    Features

    +

    The Collision Monitor uses polygons relative the robot’s base frame origin to define “zones”. +Data that fall into these zones trigger an operation depending on the model being used. +A given instance of the Collision Monitor can have many zones with different models at the same time. +When multiple zones trigger at once, the most aggressive one is used (e.g. stop > slow 50% > slow 10%).

    +

    The following models of safety behaviors are employed by Collision Monitor:

    +
      +
    • Stop model: Define a zone and a point threshold. If min_points or more obstacle points appear inside this area, stop the robot until the obstacles will disappear.

    • +
    • Slowdown model: Define a zone around the robot and slow the maximum speed for a slowdown_ratio, if min_points or more points will appear inside the area.

    • +
    • Limit model: Define a zone around the robot and restricts the maximum linear and angular velocities to linear_limit and angular_limit values accordingly, if min_points or more points will appear inside the area.

    • +
    • Approach model: Using the current robot speed, estimate the time to collision to sensor data. If the time is less than time_before_collision seconds (0.5, 2, 5, etc…), the robot will slow such that it is now at least time_before_collision seconds to collision. The effect here would be to keep the robot always time_before_collision seconds from any collision.

    • +
    +

    The zones around the robot can take the following shapes:

    +
      +
    • Arbitrary user-defined polygon relative to the robot base frame, which can be static in a configuration file or dynamically changing via a topic interface.

    • +
    • Robot footprint polygon, which is used in the approach behavior model only. Will use the static user-defined polygon or the footprint topic to allow it to be dynamically adjusted over time.

    • +
    • Circle: is made for the best performance and could be used in the cases where the zone or robot footprint could be approximated by round shape.

    • +
    +

    All shapes (Polygon and Circle) are derived from base Polygon class, so without loss of generality they would be called as “polygons”. +Subscribed footprint is also having the same properties as other polygons, but it is being obtained a footprint topic for the Approach Model.

    +

    The data may be obtained from different data sources:

    +
      +
    • Laser scanners (sensor_msgs::msg::LaserScan messages)

    • +
    • PointClouds (sensor_msgs::msg::PointCloud2 messages)

    • +
    • IR/Sonars (sensor_msgs::msg::Range messages)

    • +
    +
    +
    +

    Parameters

    +
    +
    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.

    +
    +
    +
    +
    cmd_vel_in_topic
    +
    ++++ + + + + + + + + +

    Type

    Default

    string

    “cmd_vel_raw”

    +
    +
    Description:

    Input cmd_vel topic with desired robot velocity.

    +
    +
    +
    +
    cmd_vel_out_topic
    +
    ++++ + + + + + + + + +

    Type

    Default

    string

    “cmd_vel”

    +
    +
    Description:

    Output cmd_vel topic with output produced by Collision Monitor velocities.

    +
    +
    +
    +
    state_topic
    +
    ++++ + + + + + + + + +

    Type

    Default

    string

    “”

    +
    +
    Description:

    Output the currently activated polygon action type and name. Optional parameter. No publisher will be created if it is unspecified.

    +
    +
    +
    +
    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).

    +
    +
    +
    +
    stop_pub_timeout
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    1.0

    +
    +
    Description:

    Timeout, after which zero-velocity ceases to be published. It could be used for other overrode systems outside Nav2 are trying to bring the robot out of a state close to a collision, or to allow a standing robot to go into sleep mode.

    +
    +
    +
    +
    polygons
    +
    ++++ + + + + + + + + +

    Type

    Default

    vector<string>

    N/A

    +
    +
    Description:

    List of zones (stop/slowdown/limit bounding boxes, footprint, approach circle, etc…). 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 monitor will use dynamic polygon subscription to polygon_sub_topic for points in the stop/slowdown/limit action types, or footprint subscriber to footprint_topic for approach action type.

    +
    +
    +
    +
    <polygon_name>.polygon_sub_topic
    +
    ++++ + + + + + + + + +

    Type

    Default

    string

    N/A

    +
    +
    Description:

    Topic to listen the polygon points from. Applicable only for polygon type and stop/slowdown/limit action types. 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>.footprint_topic
    +
    ++++ + + + + + + + + +

    Type

    Default

    string

    “local_costmap/published_footprint”

    +
    +
    Description:

    Topic to listen the robot footprint from. Applicable only for polygon type and approach action type. If both points and footprint_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:

    Zone behavior model. Available values are stop, slowdown, limit, approach. Causes an error, if not specialized.

    +
    +
    +
    +
    <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>.slowdown_ratio
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    0.5

    +
    +
    Description:

    Robot slowdown (share of its actual speed). Applicable for slowdown action type.

    +
    +
    +
    +
    <polygon_name>.linear_limit
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    0.5

    +
    +
    Description:

    Robot linear speed limit. Applicable for limit action type.

    +
    +
    +
    +
    <polygon_name>.angular_limit
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    0.5

    +
    +
    Description:

    Robot angular speed limit. Applicable for limit action type.

    +
    +
    +
    +
    <polygon_name>.time_before_collision
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    2.0

    +
    +
    Description:

    Time before collision in seconds. Maximum simulation time used in collision prediction. Higher values mean lower performance. Applicable for approach action type.

    +
    +
    +
    +
    <polygon_name>.simulation_time_step
    +
    ++++ + + + + + + + + +

    Type

    Default

    double

    0.1

    +
    +
    Description:

    Time iteration step for robot movement simulation during collision prediction. Higher values mean lower prediction accuracy but better performance. Applicable for approach action type.

    +
    +
    +
    +
    <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 Monitor.

    +
    collision_monitor:
    +  ros__parameters:
    +    base_frame_id: "base_footprint"
    +    odom_frame_id: "odom"
    +    cmd_vel_in_topic: "cmd_vel_raw"
    +    cmd_vel_out_topic: "cmd_vel"
    +    state_topic: "collision_monitor_state"
    +    transform_tolerance: 0.5
    +    source_timeout: 5.0
    +    base_shift_correction: True
    +    stop_pub_timeout: 2.0
    +    polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"]
    +    PolygonStop:
    +      type: "circle"
    +      radius: 0.3
    +      action_type: "stop"
    +      min_points: 4  # max_points: 3 for Humble
    +      visualize: True
    +      polygon_pub_topic: "polygon_stop"
    +    PolygonSlow:
    +      type: "polygon"
    +      points: [1.0, 1.0, 1.0, -1.0, -0.5, -1.0, -0.5, 1.0]
    +      action_type: "slowdown"
    +      min_points: 4  # max_points: 3 for Humble
    +      slowdown_ratio: 0.3
    +      visualize: True
    +      polygon_pub_topic: "polygon_slowdown"
    +    PolygonLimit:
    +      type: "polygon"
    +      points: [0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5]
    +      action_type: "limit"
    +      min_points: 4  # max_points: 3 for Humble
    +      linear_limit: 0.4
    +      angular_limit: 0.5
    +      visualize: True
    +      polygon_pub_topic: "polygon_limit"
    +    FootprintApproach:
    +      type: "polygon"
    +      action_type: "approach"
    +      footprint_topic: "/local_costmap/published_footprint"
    +      time_before_collision: 2.0
    +      simulation_time_step: 0.02
    +      min_points: 6  # max_points: 5 for Humble
    +      visualize: False
    +    observation_sources: ["scan", "pointcloud"]
    +    scan:
    +      type: "scan"
    +      topic: "/scan"
    +    pointcloud:
    +      type: "pointcloud"
    +      topic: "/intel_realsense_r200_depth/points"
    +      min_height: 0.1
    +      max_height: 0.5
    +
    +
    +
    +
    + + +
    +
    +
    + +
    + +
    +

    © Copyright 2020.

    +
    + + + +
    +
    + + +
    +
    +
    + + + + + + + + + + + + \ No newline at end of file diff --git a/configuration/packages/configuring-amcl.html b/configuration/packages/configuring-amcl.html index cfa93807a..0b0dd96db 100644 --- a/configuration/packages/configuring-amcl.html +++ b/configuration/packages/configuring-amcl.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-behavior-server.html b/configuration/packages/configuring-behavior-server.html index 024a82983..363191854 100644 --- a/configuration/packages/configuring-behavior-server.html +++ b/configuration/packages/configuring-behavior-server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-bt-navigator.html b/configuration/packages/configuring-bt-navigator.html index 579356c83..7edddebcf 100644 --- a/configuration/packages/configuring-bt-navigator.html +++ b/configuration/packages/configuring-bt-navigator.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-bt-xml.html b/configuration/packages/configuring-bt-xml.html index a38dd241a..dfbc3d8b7 100644 --- a/configuration/packages/configuring-bt-xml.html +++ b/configuration/packages/configuring-bt-xml.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-collision-monitor.html b/configuration/packages/configuring-collision-monitor.html index 3565e7627..ef0929712 100644 --- a/configuration/packages/configuring-collision-monitor.html +++ b/configuration/packages/configuring-collision-monitor.html @@ -20,7 +20,7 @@ - + @@ -689,13 +689,11 @@
  • Collision Monitor @@ -955,718 +954,19 @@

    Collision Monitor

    -

    The Collision Monitor is a node providing an additional level of robot safety. -It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level.

    -

    This is analogous to safety sensor and hardware features; take in laser scans from a real-time certified safety scanner, detect if there is to be an imminent collision in a configurable bounding box, and either emergency-stop the certified robot controller or slow the robot to avoid such collision. -However, this node is done at the CPU level with any form of sensor. -As such, this does not provide hard real-time safety certifications, but uses the same types of techniques with the same types of data for users that do not have safety-rated laser sensors, safety-rated controllers, or wish to use any type of data input (e.g. pointclouds from depth or stereo or range sensors).

    -

    This is a useful and integral part of large heavy industrial robots, or robots moving with high velocities, around people or other dynamic agents (e.g. other robots) as a safety mechanism for high-response emergency stopping. -The costmaps / trajectory planners will handle most situations, but this is to handle obstacles that virtually appear out of no where (from the robot’s perspective) or approach the robot at such high speed it needs to immediately stop to prevent collision.

    -

    See the package’s README for more complete information.

    -
    -

    Features

    -

    The Collision Monitor uses polygons relative the robot’s base frame origin to define “zones”. -Data that fall into these zones trigger an operation depending on the model being used. -A given instance of the Collision Monitor can have many zones with different models at the same time. -When multiple zones trigger at once, the most aggressive one is used (e.g. stop > slow 50% > slow 10%).

    -

    The following models of safety behaviors are employed by Collision Monitor:

    -
      -
    • Stop model: Define a zone and a point threshold. If min_points or more obstacle points appear inside this area, stop the robot until the obstacles will disappear.

    • -
    • Slowdown model: Define a zone around the robot and slow the maximum speed for a slowdown_ratio, if min_points or more points will appear inside the area.

    • -
    • Limit model: Define a zone around the robot and restricts the maximum linear and angular velocities to linear_limit and angular_limit values accordingly, if min_points or more points will appear inside the area.

    • -
    • Approach model: Using the current robot speed, estimate the time to collision to sensor data. If the time is less than time_before_collision seconds (0.5, 2, 5, etc…), the robot will slow such that it is now at least time_before_collision seconds to collision. The effect here would be to keep the robot always time_before_collision seconds from any collision.

    • -
    -

    The zones around the robot can take the following shapes:

    -
      -
    • Arbitrary user-defined polygon relative to the robot base frame, which can be static in a configuration file or dynamically changing via a topic interface.

    • -
    • Robot footprint polygon, which is used in the approach behavior model only. Will use the static user-defined polygon or the footprint topic to allow it to be dynamically adjusted over time.

    • -
    • Circle: is made for the best performance and could be used in the cases where the zone or robot footprint could be approximated by round shape.

    • -
    -

    All shapes (Polygon and Circle) are derived from base Polygon class, so without loss of generality they would be called as “polygons”. -Subscribed footprint is also having the same properties as other polygons, but it is being obtained a footprint topic for the Approach Model.

    -

    The data may be obtained from different data sources:

    -
      -
    • Laser scanners (sensor_msgs::msg::LaserScan messages)

    • -
    • PointClouds (sensor_msgs::msg::PointCloud2 messages)

    • -
    • IR/Sonars (sensor_msgs::msg::Range messages)

    • +

      Source code and README with design, explanations, and metrics can be found on Github.

      +

      The nav2_collision_monitor package contains nodes providing an additional level of robot safety, namely the Collision Monitor and the Collision Detector. +The Collision Monitor is a node providing an additional level of robot safety. It performs several collision avoidance related tasks using incoming data from the sensors, bypassing the costmap and trajectory planners, to monitor for and prevent potential collisions at the emergency-stop level. +The Collision Detector 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 a message to a topic.

      +
      +

      Provided Nodes

      +

      The nodes listed below are inside the nav2_collision_monitor package. See the pages for individual configuration information.

      + -
      -

      Parameters

      -
      -
      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.

      -
      -
      -
      -
      cmd_vel_in_topic
      -
      ---- - - - - - - - - -

      Type

      Default

      string

      “cmd_vel_raw”

      -
      -
      Description:

      Input cmd_vel topic with desired robot velocity.

      -
      -
      -
      -
      cmd_vel_out_topic
      -
      ---- - - - - - - - - -

      Type

      Default

      string

      “cmd_vel”

      -
      -
      Description:

      Output cmd_vel topic with output produced by Collision Monitor velocities.

      -
      -
      -
      -
      state_topic
      -
      ---- - - - - - - - - -

      Type

      Default

      string

      “”

      -
      -
      Description:

      Output the currently activated polygon action type and name. Optional parameter. No publisher will be created if it is unspecified.

      -
      -
      -
      -
      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).

      -
      -
      -
      -
      stop_pub_timeout
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      1.0

      -
      -
      Description:

      Timeout, after which zero-velocity ceases to be published. It could be used for other overrode systems outside Nav2 are trying to bring the robot out of a state close to a collision, or to allow a standing robot to go into sleep mode.

      -
      -
      -
      -
      polygons
      -
      ---- - - - - - - - - -

      Type

      Default

      vector<string>

      N/A

      -
      -
      Description:

      List of zones (stop/slowdown/limit bounding boxes, footprint, approach circle, etc…). 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 monitor will use dynamic polygon subscription to polygon_sub_topic for points in the stop/slowdown/limit action types, or footprint subscriber to footprint_topic for approach action type.

      -
      -
      -
      -
      <polygon_name>.polygon_sub_topic
      -
      ---- - - - - - - - - -

      Type

      Default

      string

      N/A

      -
      -
      Description:

      Topic to listen the polygon points from. Applicable only for polygon type and stop/slowdown/limit action types. 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>.footprint_topic
      -
      ---- - - - - - - - - -

      Type

      Default

      string

      “local_costmap/published_footprint”

      -
      -
      Description:

      Topic to listen the robot footprint from. Applicable only for polygon type and approach action type. If both points and footprint_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:

      Zone behavior model. Available values are stop, slowdown, limit, approach. Causes an error, if not specialized.

      -
      -
      -
      -
      <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>.slowdown_ratio
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      0.5

      -
      -
      Description:

      Robot slowdown (share of its actual speed). Applicable for slowdown action type.

      -
      -
      -
      -
      <polygon_name>.linear_limit
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      0.5

      -
      -
      Description:

      Robot linear speed limit. Applicable for limit action type.

      -
      -
      -
      -
      <polygon_name>.angular_limit
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      0.5

      -
      -
      Description:

      Robot angular speed limit. Applicable for limit action type.

      -
      -
      -
      -
      <polygon_name>.time_before_collision
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      2.0

      -
      -
      Description:

      Time before collision in seconds. Maximum simulation time used in collision prediction. Higher values mean lower performance. Applicable for approach action type.

      -
      -
      -
      -
      <polygon_name>.simulation_time_step
      -
      ---- - - - - - - - - -

      Type

      Default

      double

      0.1

      -
      -
      Description:

      Time iteration step for robot movement simulation during collision prediction. Higher values mean lower prediction accuracy but better performance. Applicable for approach action type.

      -
      -
      -
      -
      <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 Monitor. -For more information how to bring-up your own Collision Monitor node, please refer to the Using Collision Monitor tutorial.

      -
      collision_monitor:
      -  ros__parameters:
      -    base_frame_id: "base_footprint"
      -    odom_frame_id: "odom"
      -    cmd_vel_in_topic: "cmd_vel_raw"
      -    cmd_vel_out_topic: "cmd_vel"
      -    state_topic: "collision_monitor_state"
      -    transform_tolerance: 0.5
      -    source_timeout: 5.0
      -    base_shift_correction: True
      -    stop_pub_timeout: 2.0
      -    polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"]
      -    PolygonStop:
      -      type: "circle"
      -      radius: 0.3
      -      action_type: "stop"
      -      min_points: 4  # max_points: 3 for Humble
      -      visualize: True
      -      polygon_pub_topic: "polygon_stop"
      -    PolygonSlow:
      -      type: "polygon"
      -      points: [1.0, 1.0, 1.0, -1.0, -0.5, -1.0, -0.5, 1.0]
      -      action_type: "slowdown"
      -      min_points: 4  # max_points: 3 for Humble
      -      slowdown_ratio: 0.3
      -      visualize: True
      -      polygon_pub_topic: "polygon_slowdown"
      -    PolygonLimit:
      -      type: "polygon"
      -      points: [0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5]
      -      action_type: "limit"
      -      min_points: 4  # max_points: 3 for Humble
      -      linear_limit: 0.4
      -      angular_limit: 0.5
      -      visualize: True
      -      polygon_pub_topic: "polygon_limit"
      -    FootprintApproach:
      -      type: "polygon"
      -      action_type: "approach"
      -      footprint_topic: "/local_costmap/published_footprint"
      -      time_before_collision: 2.0
      -      simulation_time_step: 0.02
      -      min_points: 6  # max_points: 5 for Humble
      -      visualize: False
      -    observation_sources: ["scan", "pointcloud"]
      -    scan:
      -      type: "scan"
      -      topic: "/scan"
      -    pointcloud:
      -      type: "pointcloud"
      -      topic: "/intel_realsense_r200_depth/points"
      -      min_height: 0.1
      -      max_height: 0.5
      -
      -
      diff --git a/configuration/packages/configuring-constrained-smoother.html b/configuration/packages/configuring-constrained-smoother.html index 4a5495bf7..e912ffa26 100644 --- a/configuration/packages/configuring-constrained-smoother.html +++ b/configuration/packages/configuring-constrained-smoother.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-controller-server.html b/configuration/packages/configuring-controller-server.html index bdf85b406..004f0bee5 100644 --- a/configuration/packages/configuring-controller-server.html +++ b/configuration/packages/configuring-controller-server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-costmaps.html b/configuration/packages/configuring-costmaps.html index 5cb568e10..3d7b35a41 100644 --- a/configuration/packages/configuring-costmaps.html +++ b/configuration/packages/configuring-costmaps.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-dwb-controller.html b/configuration/packages/configuring-dwb-controller.html index 1e7af8082..1b5ee1696 100644 --- a/configuration/packages/configuring-dwb-controller.html +++ b/configuration/packages/configuring-dwb-controller.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-lifecycle.html b/configuration/packages/configuring-lifecycle.html index e44ca1f51..8004e00c5 100644 --- a/configuration/packages/configuring-lifecycle.html +++ b/configuration/packages/configuring-lifecycle.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-map-server.html b/configuration/packages/configuring-map-server.html index 7d614e384..2327623b2 100644 --- a/configuration/packages/configuring-map-server.html +++ b/configuration/packages/configuring-map-server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-mppic.html b/configuration/packages/configuring-mppic.html index 92c5001da..bef5547ab 100644 --- a/configuration/packages/configuring-mppic.html +++ b/configuration/packages/configuring-mppic.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-navfn.html b/configuration/packages/configuring-navfn.html index ab381b29b..97c3b61ab 100644 --- a/configuration/packages/configuring-navfn.html +++ b/configuration/packages/configuring-navfn.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-planner-server.html b/configuration/packages/configuring-planner-server.html index 73d1e3049..0eaf384cf 100644 --- a/configuration/packages/configuring-planner-server.html +++ b/configuration/packages/configuring-planner-server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-regulated-pp.html b/configuration/packages/configuring-regulated-pp.html index a43d61c96..ac807a40a 100644 --- a/configuration/packages/configuring-regulated-pp.html +++ b/configuration/packages/configuring-regulated-pp.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-rotation-shim-controller.html b/configuration/packages/configuring-rotation-shim-controller.html index 14c9c1289..368cdc506 100644 --- a/configuration/packages/configuring-rotation-shim-controller.html +++ b/configuration/packages/configuring-rotation-shim-controller.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-savitzky-golay-smoother.html b/configuration/packages/configuring-savitzky-golay-smoother.html index f067b1dd9..e4437d02f 100644 --- a/configuration/packages/configuring-savitzky-golay-smoother.html +++ b/configuration/packages/configuring-savitzky-golay-smoother.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-simple-smoother.html b/configuration/packages/configuring-simple-smoother.html index f86e109c1..139d1f7a1 100644 --- a/configuration/packages/configuring-simple-smoother.html +++ b/configuration/packages/configuring-simple-smoother.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-smac-planner.html b/configuration/packages/configuring-smac-planner.html index de0c8e302..ecdff5742 100644 --- a/configuration/packages/configuring-smac-planner.html +++ b/configuration/packages/configuring-smac-planner.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-smoother-server.html b/configuration/packages/configuring-smoother-server.html index 45166e3d6..d03b77f74 100644 --- a/configuration/packages/configuring-smoother-server.html +++ b/configuration/packages/configuring-smoother-server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-thetastar.html b/configuration/packages/configuring-thetastar.html index f6621d32f..6c0ef8217 100644 --- a/configuration/packages/configuring-thetastar.html +++ b/configuration/packages/configuring-thetastar.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-velocity-smoother.html b/configuration/packages/configuring-velocity-smoother.html index fe12967b5..c6ce7b437 100644 --- a/configuration/packages/configuring-velocity-smoother.html +++ b/configuration/packages/configuring-velocity-smoother.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/configuring-waypoint-follower.html b/configuration/packages/configuring-waypoint-follower.html index 38067bd68..90161ad45 100644 --- a/configuration/packages/configuring-waypoint-follower.html +++ b/configuration/packages/configuring-waypoint-follower.html @@ -21,7 +21,7 @@ - + @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/binary_filter.html b/configuration/packages/costmap-plugins/binary_filter.html index b7ec8b93d..47df0c62e 100644 --- a/configuration/packages/costmap-plugins/binary_filter.html +++ b/configuration/packages/costmap-plugins/binary_filter.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/denoise.html b/configuration/packages/costmap-plugins/denoise.html index ea26fd294..fcf157242 100644 --- a/configuration/packages/costmap-plugins/denoise.html +++ b/configuration/packages/costmap-plugins/denoise.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/inflation.html b/configuration/packages/costmap-plugins/inflation.html index 0fe05bb8d..f9f7e079a 100644 --- a/configuration/packages/costmap-plugins/inflation.html +++ b/configuration/packages/costmap-plugins/inflation.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/keepout_filter.html b/configuration/packages/costmap-plugins/keepout_filter.html index cb72a1b0a..b5df0c686 100644 --- a/configuration/packages/costmap-plugins/keepout_filter.html +++ b/configuration/packages/costmap-plugins/keepout_filter.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/obstacle.html b/configuration/packages/costmap-plugins/obstacle.html index 54dcedb87..daa99fd42 100644 --- a/configuration/packages/costmap-plugins/obstacle.html +++ b/configuration/packages/costmap-plugins/obstacle.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/range.html b/configuration/packages/costmap-plugins/range.html index 546151d55..b2fadabc9 100644 --- a/configuration/packages/costmap-plugins/range.html +++ b/configuration/packages/costmap-plugins/range.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/speed_filter.html b/configuration/packages/costmap-plugins/speed_filter.html index 737fcf14e..7ce3e5ab6 100644 --- a/configuration/packages/costmap-plugins/speed_filter.html +++ b/configuration/packages/costmap-plugins/speed_filter.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/static.html b/configuration/packages/costmap-plugins/static.html index 2ede7eb9d..040c08f07 100644 --- a/configuration/packages/costmap-plugins/static.html +++ b/configuration/packages/costmap-plugins/static.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/costmap-plugins/voxel.html b/configuration/packages/costmap-plugins/voxel.html index 103927767..fd97198b6 100644 --- a/configuration/packages/costmap-plugins/voxel.html +++ b/configuration/packages/costmap-plugins/voxel.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-params/controller.html b/configuration/packages/dwb-params/controller.html index 8617336dc..14534a2dd 100644 --- a/configuration/packages/dwb-params/controller.html +++ b/configuration/packages/dwb-params/controller.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-params/iterator.html b/configuration/packages/dwb-params/iterator.html index 006b815e8..ddc5b8703 100644 --- a/configuration/packages/dwb-params/iterator.html +++ b/configuration/packages/dwb-params/iterator.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-params/kinematic.html b/configuration/packages/dwb-params/kinematic.html index eb8fef90b..65c6d0bd7 100644 --- a/configuration/packages/dwb-params/kinematic.html +++ b/configuration/packages/dwb-params/kinematic.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-params/visualization.html b/configuration/packages/dwb-params/visualization.html index 3f4f54266..236554e58 100644 --- a/configuration/packages/dwb-params/visualization.html +++ b/configuration/packages/dwb-params/visualization.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-plugins/limited_accel_generator.html b/configuration/packages/dwb-plugins/limited_accel_generator.html index cdbd68f46..16e2a3bab 100644 --- a/configuration/packages/dwb-plugins/limited_accel_generator.html +++ b/configuration/packages/dwb-plugins/limited_accel_generator.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/dwb-plugins/standard_traj_generator.html b/configuration/packages/dwb-plugins/standard_traj_generator.html index d3e68edfe..57320c602 100644 --- a/configuration/packages/dwb-plugins/standard_traj_generator.html +++ b/configuration/packages/dwb-plugins/standard_traj_generator.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_controller-plugins/pose_progress_checker.html b/configuration/packages/nav2_controller-plugins/pose_progress_checker.html index 2346a3883..21917aaca 100644 --- a/configuration/packages/nav2_controller-plugins/pose_progress_checker.html +++ b/configuration/packages/nav2_controller-plugins/pose_progress_checker.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_controller-plugins/simple_goal_checker.html b/configuration/packages/nav2_controller-plugins/simple_goal_checker.html index 2f6196ce2..b9fcc40b5 100644 --- a/configuration/packages/nav2_controller-plugins/simple_goal_checker.html +++ b/configuration/packages/nav2_controller-plugins/simple_goal_checker.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_controller-plugins/simple_progress_checker.html b/configuration/packages/nav2_controller-plugins/simple_progress_checker.html index 8e7d6e72f..3f8f56e19 100644 --- a/configuration/packages/nav2_controller-plugins/simple_progress_checker.html +++ b/configuration/packages/nav2_controller-plugins/simple_progress_checker.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_controller-plugins/stopped_goal_checker.html b/configuration/packages/nav2_controller-plugins/stopped_goal_checker.html index 49d1265c5..83c4834a0 100644 --- a/configuration/packages/nav2_controller-plugins/stopped_goal_checker.html +++ b/configuration/packages/nav2_controller-plugins/stopped_goal_checker.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.html b/configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.html index 090b9505d..b4ee1804f 100644 --- a/configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.html +++ b/configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.html b/configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.html index c1be903ec..0e98f4b8b 100644 --- a/configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.html +++ b/configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.html b/configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.html index 13dbd180a..93d349132 100644 --- a/configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.html +++ b/configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/smac/configuring-smac-2d.html b/configuration/packages/smac/configuring-smac-2d.html index 38267b20b..adc171443 100644 --- a/configuration/packages/smac/configuring-smac-2d.html +++ b/configuration/packages/smac/configuring-smac-2d.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/smac/configuring-smac-hybrid.html b/configuration/packages/smac/configuring-smac-hybrid.html index 061171726..7fa72435b 100644 --- a/configuration/packages/smac/configuring-smac-hybrid.html +++ b/configuration/packages/smac/configuring-smac-hybrid.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/smac/configuring-smac-lattice.html b/configuration/packages/smac/configuring-smac-lattice.html index 0571e435a..ff4a5588e 100644 --- a/configuration/packages/smac/configuring-smac-lattice.html +++ b/configuration/packages/smac/configuring-smac-lattice.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/base_obstacle.html b/configuration/packages/trajectory_critics/base_obstacle.html index 7dfc3af27..18807defe 100644 --- a/configuration/packages/trajectory_critics/base_obstacle.html +++ b/configuration/packages/trajectory_critics/base_obstacle.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/goal_align.html b/configuration/packages/trajectory_critics/goal_align.html index 637e43fc6..3e0fb2311 100644 --- a/configuration/packages/trajectory_critics/goal_align.html +++ b/configuration/packages/trajectory_critics/goal_align.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/goal_dist.html b/configuration/packages/trajectory_critics/goal_dist.html index 29365e9c3..82d9898fd 100644 --- a/configuration/packages/trajectory_critics/goal_dist.html +++ b/configuration/packages/trajectory_critics/goal_dist.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/obstacle_footprint.html b/configuration/packages/trajectory_critics/obstacle_footprint.html index bdf106835..83e58eabf 100644 --- a/configuration/packages/trajectory_critics/obstacle_footprint.html +++ b/configuration/packages/trajectory_critics/obstacle_footprint.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/oscillation.html b/configuration/packages/trajectory_critics/oscillation.html index e7962e51a..5ceec1fc8 100644 --- a/configuration/packages/trajectory_critics/oscillation.html +++ b/configuration/packages/trajectory_critics/oscillation.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/path_align.html b/configuration/packages/trajectory_critics/path_align.html index 82504c9ca..36a37453f 100644 --- a/configuration/packages/trajectory_critics/path_align.html +++ b/configuration/packages/trajectory_critics/path_align.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/path_dist.html b/configuration/packages/trajectory_critics/path_dist.html index 584135737..7b5cf8be4 100644 --- a/configuration/packages/trajectory_critics/path_dist.html +++ b/configuration/packages/trajectory_critics/path_dist.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/prefer_forward.html b/configuration/packages/trajectory_critics/prefer_forward.html index b199833b8..d87484af9 100644 --- a/configuration/packages/trajectory_critics/prefer_forward.html +++ b/configuration/packages/trajectory_critics/prefer_forward.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/rotate_to_goal.html b/configuration/packages/trajectory_critics/rotate_to_goal.html index e7e6a3f45..e292abca0 100644 --- a/configuration/packages/trajectory_critics/rotate_to_goal.html +++ b/configuration/packages/trajectory_critics/rotate_to_goal.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/configuration/packages/trajectory_critics/twirling.html b/configuration/packages/trajectory_critics/twirling.html index 3381054b0..7c3de993f 100644 --- a/configuration/packages/trajectory_critics/twirling.html +++ b/configuration/packages/trajectory_critics/twirling.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/build_docs/build_troubleshooting_guide.html b/development_guides/build_docs/build_troubleshooting_guide.html index fec9825ba..254a80531 100644 --- a/development_guides/build_docs/build_troubleshooting_guide.html +++ b/development_guides/build_docs/build_troubleshooting_guide.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/build_docs/index.html b/development_guides/build_docs/index.html index c9d71d333..bb6a65781 100644 --- a/development_guides/build_docs/index.html +++ b/development_guides/build_docs/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/devcontainer_docs/devcontainer_guide.html b/development_guides/devcontainer_docs/devcontainer_guide.html index 2cc46585c..3c81aea53 100644 --- a/development_guides/devcontainer_docs/devcontainer_guide.html +++ b/development_guides/devcontainer_docs/devcontainer_guide.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/devcontainer_docs/index.html b/development_guides/devcontainer_docs/index.html index 03481022a..31886c2c2 100644 --- a/development_guides/devcontainer_docs/index.html +++ b/development_guides/devcontainer_docs/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/index.html b/development_guides/index.html index 5ad70a145..69fc37a6e 100644 --- a/development_guides/index.html +++ b/development_guides/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/development_guides/involvement_docs/index.html b/development_guides/involvement_docs/index.html index b7afcc2a1..527554634 100644 --- a/development_guides/involvement_docs/index.html +++ b/development_guides/involvement_docs/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/genindex.html b/genindex.html index 6fc2e7d5e..fb8c51ba9 100644 --- a/genindex.html +++ b/genindex.html @@ -687,13 +687,11 @@
  • Collision Monitor diff --git a/getting_started/index.html b/getting_started/index.html index 3c1b41e20..d81ef5c28 100644 --- a/getting_started/index.html +++ b/getting_started/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/index.html b/index.html index d11c48c95..9235b9c81 100644 --- a/index.html +++ b/index.html @@ -688,13 +688,11 @@
  • Collision Monitor diff --git a/migration/Dashing.html b/migration/Dashing.html index d4b858952..8aef69cfe 100644 --- a/migration/Dashing.html +++ b/migration/Dashing.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/migration/Eloquent.html b/migration/Eloquent.html index 124e5a3be..35f1a1e1f 100644 --- a/migration/Eloquent.html +++ b/migration/Eloquent.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/migration/Foxy.html b/migration/Foxy.html index d166244f9..73e6dc0f3 100644 --- a/migration/Foxy.html +++ b/migration/Foxy.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/migration/Galactic.html b/migration/Galactic.html index 5c6b23803..8816dc946 100644 --- a/migration/Galactic.html +++ b/migration/Galactic.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/migration/Humble.html b/migration/Humble.html index b0987be7b..0de48a0f6 100644 --- a/migration/Humble.html +++ b/migration/Humble.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/migration/Iron.html b/migration/Iron.html index 1f54ab8d2..169a7c810 100644 --- a/migration/Iron.html +++ b/migration/Iron.html @@ -689,13 +689,11 @@
  • Collision Monitor @@ -1003,6 +1002,11 @@

    Allow Behavior Server Plugins to Access The Action Result

    debug_visualizations replaces viz_expansions parameter in Hybrid-A* to reflect the new inclusion of footprint debug information being published as well.

    +
    +

    New node in nav2_collision_monitor: Collision Detector

    +

    In this PR #3693 A new node was introduced in the nav2_collision_monitor: Collision Detector. +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 that might be used by any external module (e.g. switching LED or sound alarm in case of collision).

    +
    diff --git a/migration/index.html b/migration/index.html index 66366c4d0..3298f0ab6 100644 --- a/migration/index.html +++ b/migration/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/objects.inv b/objects.inv index cf5b254ae..2735911c3 100644 Binary files a/objects.inv and b/objects.inv differ diff --git a/plugin_tutorials/docs/writing_new_behavior_plugin.html b/plugin_tutorials/docs/writing_new_behavior_plugin.html index d0d8d6257..30183a269 100644 --- a/plugin_tutorials/docs/writing_new_behavior_plugin.html +++ b/plugin_tutorials/docs/writing_new_behavior_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/docs/writing_new_bt_plugin.html b/plugin_tutorials/docs/writing_new_bt_plugin.html index c73e1a303..2e3bd8c87 100644 --- a/plugin_tutorials/docs/writing_new_bt_plugin.html +++ b/plugin_tutorials/docs/writing_new_bt_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/docs/writing_new_costmap2d_plugin.html b/plugin_tutorials/docs/writing_new_costmap2d_plugin.html index 229381596..fbe11174f 100644 --- a/plugin_tutorials/docs/writing_new_costmap2d_plugin.html +++ b/plugin_tutorials/docs/writing_new_costmap2d_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/docs/writing_new_nav2controller_plugin.html b/plugin_tutorials/docs/writing_new_nav2controller_plugin.html index f9f1530f7..ddb5b1ebd 100644 --- a/plugin_tutorials/docs/writing_new_nav2controller_plugin.html +++ b/plugin_tutorials/docs/writing_new_nav2controller_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/docs/writing_new_nav2planner_plugin.html b/plugin_tutorials/docs/writing_new_nav2planner_plugin.html index 23a0d5145..370f7fce3 100644 --- a/plugin_tutorials/docs/writing_new_nav2planner_plugin.html +++ b/plugin_tutorials/docs/writing_new_nav2planner_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/docs/writing_new_navigator_plugin.html b/plugin_tutorials/docs/writing_new_navigator_plugin.html index 452e7c2c2..070191457 100644 --- a/plugin_tutorials/docs/writing_new_navigator_plugin.html +++ b/plugin_tutorials/docs/writing_new_navigator_plugin.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugin_tutorials/index.html b/plugin_tutorials/index.html index 3af4c4567..1c065cdd2 100644 --- a/plugin_tutorials/index.html +++ b/plugin_tutorials/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/plugins/index.html b/plugins/index.html index 27486f42d..c8f0450f4 100644 --- a/plugins/index.html +++ b/plugins/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/roadmap/roadmap.html b/roadmap/roadmap.html index f3d5e7de9..ef38650ab 100644 --- a/roadmap/roadmap.html +++ b/roadmap/roadmap.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/search.html b/search.html index cfd74f366..d2e8c8b17 100644 --- a/search.html +++ b/search.html @@ -690,13 +690,11 @@
  • Collision Monitor diff --git a/searchindex.js b/searchindex.js index 7ac2378b8..34d5221a6 100644 --- a/searchindex.js +++ b/searchindex.js @@ -1 +1 @@ -Search.setIndex({docnames:["2021summerOfCode/Summer_2021_Student_Program","2021summerOfCode/projects/assisted_teleop","2021summerOfCode/projects/create_configuration_assistant","2021summerOfCode/projects/create_plugins","2021summerOfCode/projects/dynamic","2021summerOfCode/projects/grid_maps","2021summerOfCode/projects/localization","2021summerOfCode/projects/multithreading","2021summerOfCode/projects/navigation_rebranding","2021summerOfCode/projects/safety_node","2021summerOfCode/projects/semantics","2021summerOfCode/projects/spinners","2021summerOfCode/projects/testing","2021summerOfCode/projects/twist_n_config","about/index","about/related_projects","about/robots","about/ros1_comparison","behavior_trees/index","behavior_trees/overview/detailed_behavior_tree_walkthrough","behavior_trees/overview/nav2_specific_nodes","behavior_trees/trees/follow_point","behavior_trees/trees/nav_through_poses_recovery","behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle","behavior_trees/trees/nav_to_pose_recovery","behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid","behavior_trees/trees/odometry_calibration","commander_api/index","concepts/index","configuration/index","configuration/packages/bt-plugins/actions/AssistedTeleop","configuration/packages/bt-plugins/actions/BackUp","configuration/packages/bt-plugins/actions/CancelAssistedTeleop","configuration/packages/bt-plugins/actions/CancelBackUp","configuration/packages/bt-plugins/actions/CancelControl","configuration/packages/bt-plugins/actions/CancelDriveOnHeading","configuration/packages/bt-plugins/actions/CancelSpin","configuration/packages/bt-plugins/actions/CancelWait","configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot","configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion","configuration/packages/bt-plugins/actions/ClearEntireCostmap","configuration/packages/bt-plugins/actions/ComputePathThroughPoses","configuration/packages/bt-plugins/actions/ComputePathToPose","configuration/packages/bt-plugins/actions/ControllerSelector","configuration/packages/bt-plugins/actions/DriveOnHeading","configuration/packages/bt-plugins/actions/FollowPath","configuration/packages/bt-plugins/actions/GoalCheckerSelector","configuration/packages/bt-plugins/actions/NavigateThroughPoses","configuration/packages/bt-plugins/actions/NavigateToPose","configuration/packages/bt-plugins/actions/PlannerSelector","configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization","configuration/packages/bt-plugins/actions/RemovePassedGoals","configuration/packages/bt-plugins/actions/Smooth","configuration/packages/bt-plugins/actions/SmootherSelector","configuration/packages/bt-plugins/actions/Spin","configuration/packages/bt-plugins/actions/TruncatePath","configuration/packages/bt-plugins/actions/TruncatePathLocal","configuration/packages/bt-plugins/actions/Wait","configuration/packages/bt-plugins/conditions/AreErrorCodesPresent","configuration/packages/bt-plugins/conditions/DistanceTraveled","configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal","configuration/packages/bt-plugins/conditions/GoalReached","configuration/packages/bt-plugins/conditions/GoalUpdated","configuration/packages/bt-plugins/conditions/InitialPoseReceived","configuration/packages/bt-plugins/conditions/IsBatteryCharging","configuration/packages/bt-plugins/conditions/IsBatteryLow","configuration/packages/bt-plugins/conditions/IsPathValid","configuration/packages/bt-plugins/conditions/IsStuck","configuration/packages/bt-plugins/conditions/PathExpiringTimer","configuration/packages/bt-plugins/conditions/TimeExpired","configuration/packages/bt-plugins/conditions/TransformAvailable","configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp","configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp","configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp","configuration/packages/bt-plugins/controls/PipelineSequence","configuration/packages/bt-plugins/controls/RecoveryNode","configuration/packages/bt-plugins/controls/RoundRobin","configuration/packages/bt-plugins/decorators/DistanceController","configuration/packages/bt-plugins/decorators/GoalUpdater","configuration/packages/bt-plugins/decorators/PathLongerOnApproach","configuration/packages/bt-plugins/decorators/RateController","configuration/packages/bt-plugins/decorators/SingleTrigger","configuration/packages/bt-plugins/decorators/SpeedController","configuration/packages/configuring-amcl","configuration/packages/configuring-behavior-server","configuration/packages/configuring-bt-navigator","configuration/packages/configuring-bt-xml","configuration/packages/configuring-collision-monitor","configuration/packages/configuring-constrained-smoother","configuration/packages/configuring-controller-server","configuration/packages/configuring-costmaps","configuration/packages/configuring-dwb-controller","configuration/packages/configuring-lifecycle","configuration/packages/configuring-map-server","configuration/packages/configuring-mppic","configuration/packages/configuring-navfn","configuration/packages/configuring-planner-server","configuration/packages/configuring-regulated-pp","configuration/packages/configuring-rotation-shim-controller","configuration/packages/configuring-savitzky-golay-smoother","configuration/packages/configuring-simple-smoother","configuration/packages/configuring-smac-planner","configuration/packages/configuring-smoother-server","configuration/packages/configuring-thetastar","configuration/packages/configuring-velocity-smoother","configuration/packages/configuring-waypoint-follower","configuration/packages/costmap-plugins/binary_filter","configuration/packages/costmap-plugins/denoise","configuration/packages/costmap-plugins/inflation","configuration/packages/costmap-plugins/keepout_filter","configuration/packages/costmap-plugins/obstacle","configuration/packages/costmap-plugins/range","configuration/packages/costmap-plugins/speed_filter","configuration/packages/costmap-plugins/static","configuration/packages/costmap-plugins/voxel","configuration/packages/dwb-params/controller","configuration/packages/dwb-params/iterator","configuration/packages/dwb-params/kinematic","configuration/packages/dwb-params/visualization","configuration/packages/dwb-plugins/limited_accel_generator","configuration/packages/dwb-plugins/standard_traj_generator","configuration/packages/nav2_controller-plugins/pose_progress_checker","configuration/packages/nav2_controller-plugins/simple_goal_checker","configuration/packages/nav2_controller-plugins/simple_progress_checker","configuration/packages/nav2_controller-plugins/stopped_goal_checker","configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint","configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint","configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint","configuration/packages/smac/configuring-smac-2d","configuration/packages/smac/configuring-smac-hybrid","configuration/packages/smac/configuring-smac-lattice","configuration/packages/trajectory_critics/base_obstacle","configuration/packages/trajectory_critics/goal_align","configuration/packages/trajectory_critics/goal_dist","configuration/packages/trajectory_critics/obstacle_footprint","configuration/packages/trajectory_critics/oscillation","configuration/packages/trajectory_critics/path_align","configuration/packages/trajectory_critics/path_dist","configuration/packages/trajectory_critics/prefer_forward","configuration/packages/trajectory_critics/rotate_to_goal","configuration/packages/trajectory_critics/twirling","development_guides/build_docs/build_troubleshooting_guide","development_guides/build_docs/index","development_guides/devcontainer_docs/devcontainer_guide","development_guides/devcontainer_docs/index","development_guides/index","development_guides/involvement_docs/index","getting_started/index","index","migration/Dashing","migration/Eloquent","migration/Foxy","migration/Galactic","migration/Humble","migration/Iron","migration/index","plugin_tutorials/docs/writing_new_behavior_plugin","plugin_tutorials/docs/writing_new_bt_plugin","plugin_tutorials/docs/writing_new_costmap2d_plugin","plugin_tutorials/docs/writing_new_nav2controller_plugin","plugin_tutorials/docs/writing_new_nav2planner_plugin","plugin_tutorials/docs/writing_new_navigator_plugin","plugin_tutorials/index","plugins/index","roadmap/roadmap","setup_guides/algorithm/select_algorithm","setup_guides/footprint/setup_footprint","setup_guides/index","setup_guides/odom/setup_odom","setup_guides/sensors/setup_sensors","setup_guides/transformation/setup_transforms","setup_guides/urdf/setup_urdf","tuning/index","tutorials/docs/adding_a_nav2_task_server","tutorials/docs/adding_smoother","tutorials/docs/camera_calibration","tutorials/docs/filtering_of_noise-induced_obstacles","tutorials/docs/get_backtrace","tutorials/docs/get_profile","tutorials/docs/navigation2_dynamic_point_following","tutorials/docs/navigation2_on_real_turtlebot3","tutorials/docs/navigation2_with_keepout_filter","tutorials/docs/navigation2_with_slam","tutorials/docs/navigation2_with_speed_filter","tutorials/docs/navigation2_with_stvl","tutorials/docs/using_collision_monitor","tutorials/docs/using_groot","tutorials/docs/using_shim_controller","tutorials/index"],envversion:{"sphinx.domains.c":2,"sphinx.domains.changeset":1,"sphinx.domains.citation":1,"sphinx.domains.cpp":3,"sphinx.domains.index":1,"sphinx.domains.javascript":2,"sphinx.domains.math":2,"sphinx.domains.python":2,"sphinx.domains.rst":2,"sphinx.domains.std":2,sphinx:56},filenames:["2021summerOfCode/Summer_2021_Student_Program.rst","2021summerOfCode/projects/assisted_teleop.rst","2021summerOfCode/projects/create_configuration_assistant.rst","2021summerOfCode/projects/create_plugins.rst","2021summerOfCode/projects/dynamic.rst","2021summerOfCode/projects/grid_maps.rst","2021summerOfCode/projects/localization.rst","2021summerOfCode/projects/multithreading.rst","2021summerOfCode/projects/navigation_rebranding.rst","2021summerOfCode/projects/safety_node.rst","2021summerOfCode/projects/semantics.rst","2021summerOfCode/projects/spinners.rst","2021summerOfCode/projects/testing.rst","2021summerOfCode/projects/twist_n_config.rst","about/index.rst","about/related_projects.rst","about/robots.rst","about/ros1_comparison.rst","behavior_trees/index.rst","behavior_trees/overview/detailed_behavior_tree_walkthrough.rst","behavior_trees/overview/nav2_specific_nodes.rst","behavior_trees/trees/follow_point.rst","behavior_trees/trees/nav_through_poses_recovery.rst","behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst","behavior_trees/trees/nav_to_pose_recovery.rst","behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst","behavior_trees/trees/odometry_calibration.rst","commander_api/index.rst","concepts/index.rst","configuration/index.rst","configuration/packages/bt-plugins/actions/AssistedTeleop.rst","configuration/packages/bt-plugins/actions/BackUp.rst","configuration/packages/bt-plugins/actions/CancelAssistedTeleop.rst","configuration/packages/bt-plugins/actions/CancelBackUp.rst","configuration/packages/bt-plugins/actions/CancelControl.rst","configuration/packages/bt-plugins/actions/CancelDriveOnHeading.rst","configuration/packages/bt-plugins/actions/CancelSpin.rst","configuration/packages/bt-plugins/actions/CancelWait.rst","configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.rst","configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.rst","configuration/packages/bt-plugins/actions/ClearEntireCostmap.rst","configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst","configuration/packages/bt-plugins/actions/ComputePathToPose.rst","configuration/packages/bt-plugins/actions/ControllerSelector.rst","configuration/packages/bt-plugins/actions/DriveOnHeading.rst","configuration/packages/bt-plugins/actions/FollowPath.rst","configuration/packages/bt-plugins/actions/GoalCheckerSelector.rst","configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst","configuration/packages/bt-plugins/actions/NavigateToPose.rst","configuration/packages/bt-plugins/actions/PlannerSelector.rst","configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.rst","configuration/packages/bt-plugins/actions/RemovePassedGoals.rst","configuration/packages/bt-plugins/actions/Smooth.rst","configuration/packages/bt-plugins/actions/SmootherSelector.rst","configuration/packages/bt-plugins/actions/Spin.rst","configuration/packages/bt-plugins/actions/TruncatePath.rst","configuration/packages/bt-plugins/actions/TruncatePathLocal.rst","configuration/packages/bt-plugins/actions/Wait.rst","configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.rst","configuration/packages/bt-plugins/conditions/DistanceTraveled.rst","configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.rst","configuration/packages/bt-plugins/conditions/GoalReached.rst","configuration/packages/bt-plugins/conditions/GoalUpdated.rst","configuration/packages/bt-plugins/conditions/InitialPoseReceived.rst","configuration/packages/bt-plugins/conditions/IsBatteryCharging.rst","configuration/packages/bt-plugins/conditions/IsBatteryLow.rst","configuration/packages/bt-plugins/conditions/IsPathValid.rst","configuration/packages/bt-plugins/conditions/IsStuck.rst","configuration/packages/bt-plugins/conditions/PathExpiringTimer.rst","configuration/packages/bt-plugins/conditions/TimeExpired.rst","configuration/packages/bt-plugins/conditions/TransformAvailable.rst","configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.rst","configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.rst","configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.rst","configuration/packages/bt-plugins/controls/PipelineSequence.rst","configuration/packages/bt-plugins/controls/RecoveryNode.rst","configuration/packages/bt-plugins/controls/RoundRobin.rst","configuration/packages/bt-plugins/decorators/DistanceController.rst","configuration/packages/bt-plugins/decorators/GoalUpdater.rst","configuration/packages/bt-plugins/decorators/PathLongerOnApproach.rst","configuration/packages/bt-plugins/decorators/RateController.rst","configuration/packages/bt-plugins/decorators/SingleTrigger.rst","configuration/packages/bt-plugins/decorators/SpeedController.rst","configuration/packages/configuring-amcl.rst","configuration/packages/configuring-behavior-server.rst","configuration/packages/configuring-bt-navigator.rst","configuration/packages/configuring-bt-xml.rst","configuration/packages/configuring-collision-monitor.rst","configuration/packages/configuring-constrained-smoother.rst","configuration/packages/configuring-controller-server.rst","configuration/packages/configuring-costmaps.rst","configuration/packages/configuring-dwb-controller.rst","configuration/packages/configuring-lifecycle.rst","configuration/packages/configuring-map-server.rst","configuration/packages/configuring-mppic.rst","configuration/packages/configuring-navfn.rst","configuration/packages/configuring-planner-server.rst","configuration/packages/configuring-regulated-pp.rst","configuration/packages/configuring-rotation-shim-controller.rst","configuration/packages/configuring-savitzky-golay-smoother.rst","configuration/packages/configuring-simple-smoother.rst","configuration/packages/configuring-smac-planner.rst","configuration/packages/configuring-smoother-server.rst","configuration/packages/configuring-thetastar.rst","configuration/packages/configuring-velocity-smoother.rst","configuration/packages/configuring-waypoint-follower.rst","configuration/packages/costmap-plugins/binary_filter.rst","configuration/packages/costmap-plugins/denoise.rst","configuration/packages/costmap-plugins/inflation.rst","configuration/packages/costmap-plugins/keepout_filter.rst","configuration/packages/costmap-plugins/obstacle.rst","configuration/packages/costmap-plugins/range.rst","configuration/packages/costmap-plugins/speed_filter.rst","configuration/packages/costmap-plugins/static.rst","configuration/packages/costmap-plugins/voxel.rst","configuration/packages/dwb-params/controller.rst","configuration/packages/dwb-params/iterator.rst","configuration/packages/dwb-params/kinematic.rst","configuration/packages/dwb-params/visualization.rst","configuration/packages/dwb-plugins/limited_accel_generator.rst","configuration/packages/dwb-plugins/standard_traj_generator.rst","configuration/packages/nav2_controller-plugins/pose_progress_checker.rst","configuration/packages/nav2_controller-plugins/simple_goal_checker.rst","configuration/packages/nav2_controller-plugins/simple_progress_checker.rst","configuration/packages/nav2_controller-plugins/stopped_goal_checker.rst","configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.rst","configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.rst","configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.rst","configuration/packages/smac/configuring-smac-2d.rst","configuration/packages/smac/configuring-smac-hybrid.rst","configuration/packages/smac/configuring-smac-lattice.rst","configuration/packages/trajectory_critics/base_obstacle.rst","configuration/packages/trajectory_critics/goal_align.rst","configuration/packages/trajectory_critics/goal_dist.rst","configuration/packages/trajectory_critics/obstacle_footprint.rst","configuration/packages/trajectory_critics/oscillation.rst","configuration/packages/trajectory_critics/path_align.rst","configuration/packages/trajectory_critics/path_dist.rst","configuration/packages/trajectory_critics/prefer_forward.rst","configuration/packages/trajectory_critics/rotate_to_goal.rst","configuration/packages/trajectory_critics/twirling.rst","development_guides/build_docs/build_troubleshooting_guide.rst","development_guides/build_docs/index.rst","development_guides/devcontainer_docs/devcontainer_guide.md","development_guides/devcontainer_docs/index.md","development_guides/index.rst","development_guides/involvement_docs/index.rst","getting_started/index.rst","index.rst","migration/Dashing.rst","migration/Eloquent.rst","migration/Foxy.rst","migration/Galactic.rst","migration/Humble.rst","migration/Iron.rst","migration/index.rst","plugin_tutorials/docs/writing_new_behavior_plugin.rst","plugin_tutorials/docs/writing_new_bt_plugin.rst","plugin_tutorials/docs/writing_new_costmap2d_plugin.rst","plugin_tutorials/docs/writing_new_nav2controller_plugin.rst","plugin_tutorials/docs/writing_new_nav2planner_plugin.rst","plugin_tutorials/docs/writing_new_navigator_plugin.rst","plugin_tutorials/index.rst","plugins/index.rst","roadmap/roadmap.rst","setup_guides/algorithm/select_algorithm.rst","setup_guides/footprint/setup_footprint.rst","setup_guides/index.rst","setup_guides/odom/setup_odom.rst","setup_guides/sensors/setup_sensors.rst","setup_guides/transformation/setup_transforms.rst","setup_guides/urdf/setup_urdf.rst","tuning/index.rst","tutorials/docs/adding_a_nav2_task_server.rst","tutorials/docs/adding_smoother.rst","tutorials/docs/camera_calibration.rst","tutorials/docs/filtering_of_noise-induced_obstacles.rst","tutorials/docs/get_backtrace.rst","tutorials/docs/get_profile.rst","tutorials/docs/navigation2_dynamic_point_following.rst","tutorials/docs/navigation2_on_real_turtlebot3.rst","tutorials/docs/navigation2_with_keepout_filter.rst","tutorials/docs/navigation2_with_slam.rst","tutorials/docs/navigation2_with_speed_filter.rst","tutorials/docs/navigation2_with_stvl.rst","tutorials/docs/using_collision_monitor.rst","tutorials/docs/using_groot.rst","tutorials/docs/using_shim_controller.rst","tutorials/index.rst"],objects:{},objnames:{},objtypes:{},terms:{"000":[168,170],"000000":169,"0000008":168,"0000075":168,"0001":89,"001":[83,89,91,97,98,168,169,187],"002":168,"003":168,"005":83,"015":[88,94,129,130,169],"015000":169,"022":169,"025":[19,22,24,27,31,44,86,91,120,171],"035":169,"047198":169,"048":184,"0508":169,"055":169,"05s":94,"092":168,"0_1602582820":126,"0x000055555555828b":177,"0x0000555555558e1d":177,"0x000055555555936c":177,"0x0000555555559cfc":177,"0x00007ffff79cc859":177,"0x00007ffff7c52951":177,"0x00007ffff7c553eb":177,"0x00007ffff7c5e47c":177,"0x00007ffff7c5e4e7":177,"0x00007ffff7c5e799":177,"0x5555555cfb40":177,"0x5555555cfdb0":177,"0x7fffffffc108":177,"100":[83,87,88,90,94,112,153,168,170,173,177,179,181,183,186],"1000":[94,100,128,129,130],"10000":[94,153,173],"1000000":[128,129,130],"10001":173,"10002":173,"1001":153,"10099":173,"100hz":19,"100m":[27,101,152],"101":[58,153,173,181],"103":[151,170],"105":[28,148,168,170],"107":58,"1070":177,"1091":177,"10cm":[128,129,170],"113m":101,"119":58,"120000":169,"124":158,"125":[128,169],"1263":151,"127":168,"128":171,"12th":168,"12thread":152,"130":169,"144m":101,"146m":101,"160":171,"164":171,"1660":150,"171":158,"1780":150,"1784":150,"180":87,"185":88,"1855":151,"1859":150,"188":[181,183],"1882":151,"195":166,"196":183,"199":[153,173],"1ms":99,"1st":168,"200":[170,173],"2000":[83,94],"2000000":88,"2005":164,"200m":[101,152],"201":[153,173],"2020":148,"2021":[101,143,148,172,184],"2023":[97,148],"204":172,"20cm":170,"20hz":94,"20m":170,"20mm":175,"215":169,"2181":151,"2204":151,"2247":151,"2263":151,"2264":151,"2295":151,"2338":151,"2411":152,"243m":101,"2473":152,"2481":152,"2488":152,"254":169,"255":[90,158,181],"2567":153,"2569":152,"2591":152,"2592":152,"25hz":152,"2607":152,"2627":152,"2642":152,"2665":152,"2696":152,"2701":152,"2704":152,"2718":152,"2750":152,"2752":152,"2753":152,"2772":152,"2787":152,"280000":169,"2804":152,"2856":152,"2865":152,"2867":152,"2875":152,"2904":152,"2964":152,"2965":152,"2976":152,"2982":153,"299":[153,173],"2992":152,"2nd":168,"300":[172,173],"301":[153,173],"30hz":94,"3131":153,"3146":153,"3159":153,"3165":153,"3168":153,"3174":153,"3201":153,"3204":153,"3218":153,"3219":153,"3222":153,"3227":153,"3228":153,"3229":153,"3248":153,"325":[132,136],"3251":153,"3255":153,"3283":153,"32gb":152,"3320":153,"3324":153,"333":22,"3345":153,"3374":153,"3414":153,"3504":153,"3512":153,"3513":153,"3519":153,"3530":153,"3553":153,"3555":153,"3569":153,"3572":154,"3577":153,"360":169,"3612":154,"3693":154,"3704":154,"399":[153,173],"3rd":168,"40hz":9,"40x":[129,130],"46m":103,"480":169,"4th":94,"500":[83,173],"501":[153,173],"50m":152,"557":171,"570796":26,"599":[153,173],"5cm":[94,128,129],"5e3":88,"600":[27,152,173],"601":[153,173],"640":169,"65535":[153,173],"699":[153,173],"6core":152,"701":[153,173],"709":153,"710":153,"719":153,"720":153,"729":153,"730":153,"739":153,"785":[97,98,187],"799":173,"7x7":175,"7x9":175,"801":153,"816":152,"842000000":168,"8700":152,"8745":184,"8x10":175,"901":153,"9900":173,"9901":173,"996":168,"9999":[153,173],"abstract":[5,11,28,152,153,186],"boolean":[28,106,153,163,169],"break":[100,151,153],"case":[1,6,12,19,20,22,28,30,31,44,50,54,64,87,94,97,99,112,115,122,128,129,130,143,148,150,151,156,157,158,159,161,163,166,168,169,170,171,173,176,177,178,179,180,181,183,185,186],"catch":[27,152],"char":158,"class":[28,83,85,87,148,150,151,152,153,156,157,158,159,160,161,171,172,184],"const":[152,156,157,159,161],"default":[15,18,19,20,27,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,65,69,70,71,72,73,75,77,78,79,80,82,83,85,87,88,91,92,93,94,95,97,98,99,100,102,103,104,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,142,143,144,147,149,150,152,154,157,158,161,163,165,166,168,169,172,175,176,179,181,185,186],"enum":[93,94,110,114,129,153,173],"export":[142,147,180,182,184,186],"final":[22,23,27,28,92,94,128,129,130,143,151,157,161,169,172,173,174,187],"float":27,"function":[1,3,4,9,11,18,23,27,28,88,89,94,101,103,129,130,150,151,152,153,156,157,158,159,160,161,163,165,166,168,169,170,172,176,177,178,181,183,186],"gin\u00e9":148,"goto":[158,159,160,161],"i\u00f1igo":163,"import":[11,18,27,28,88,94,101,104,142,143,146,161,164,166,169,170,171,172,173,176,177,178,181,183,186,187],"int":[27,75,83,85,87,88,90,93,94,99,100,103,105,107,110,114,116,127,128,129,130,157,158,160,161,177],"long":[2,4,9,14,23,28,101,110,114,118,152,161,165,169,172,176],"mart\u00edn":[148,163],"new":[1,4,5,6,8,9,11,14,17,18,19,21,22,24,25,27,28,84,85,94,98,110,114,141,143,144,146,162,163,164,165,166,167,168,169,170,171,172,174,177,179,180,181,182,183,184,186,187,188],"public":[146,158,173],"r\u00f6smann":163,"return":[19,20,22,23,24,25,27,28,52,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,77,80,81,82,94,110,114,128,129,130,149,151,152,153,156,157,159,160,161,163,168,169,171,173,174,177,181,183],"short":[19,58,71,72,73,130,156,169,170,186],"static":[3,28,83,87,90,110,114,129,130,146,148,152,154,157,163,166,169,172,173,176,184,185],"switch":[27,94,106,143,144,150,151,152,153],"throw":[27,89,152,153,177],"transient":[22,24,25,43,46,49,53],"true":[8,20,27,28,30,52,54,65,83,85,87,88,89,90,91,92,94,95,97,98,99,100,102,103,105,106,107,108,109,110,111,112,113,114,115,118,120,122,125,126,127,128,129,130,147,151,152,153,154,156,157,158,159,160,161,166,168,169,171,172,173,174,176,178,181,182,183,184,185,187],"try":[19,21,22,24,25,27,87,92,94,104,105,129,130,141,143,147,149,170,171,177,179,181,186],"void":[152,157,159,161],"while":[7,9,13,19,22,24,25,27,85,92,94,97,99,109,139,142,143,144,151,152,153,157,161,165,166,168,169,172,173,174,176,177,180,181,185,186,187,188],ADE:144,Adding:[153,177,188],And:[18,19,154,170,171,174,175,176,181],Are:[110,114,163],Axes:171,BTs:[19,20,163,173,186],BUT:19,DDS:[11,143],For:[0,14,19,20,28,83,87,89,90,91,94,97,98,99,101,103,106,109,112,126,129,130,142,143,144,146,147,151,152,156,157,158,159,160,161,163,164,165,166,167,168,169,170,171,172,173,174,176,177,179,181,182,183,184,185,187],GPS:[15,28,168,169],IDE:[144,177],IDEs:[144,177],IDs:161,Its:[94,161,171,176],LTS:147,NOT:[110,114],Near:18,Not:[56,94,148],One:[28,165,168,171],PMs:146,PRs:[13,146,152,153],QoS:[43,46,49,53,113,151,169],ROS:[0,1,2,3,4,6,7,8,9,10,12,13,14,15,20,22,24,25,27,30,31,41,42,44,45,47,48,54,57,91,93,101,141,142,143,144,146,147,148,149,150,151,152,154,156,157,158,159,160,161,163,164,165,167,168,169,170,171,172,173,174,175,176,180,181,182,183,184,186,187,188],SMS:[28,156],Such:143,TLS:184,That:[20,146,151,152,165],The:[0,3,4,6,7,8,9,10,12,13,17,19,20,21,22,23,24,25,26,27,28,30,31,32,33,34,35,36,37,41,42,43,44,45,46,47,48,49,51,52,53,55,56,58,59,68,69,71,72,73,75,77,78,80,82,83,84,85,86,87,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,112,126,128,129,130,141,142,143,146,148,149,150,151,152,153,156,157,158,159,160,161,163,165,166,167,168,169,170,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],Then:[7,20,151,157,158,159,160,161,168,169,177,178,180],There:[3,14,19,20,28,93,94,141,142,146,149,151,152,158,163,165,169,170,177,181,187],These:[17,18,19,28,94,143,148,149,150,151,152,153,157,158,159,161,165,167,168,169,170,171,172,173,174,177,178,181,183,186],Use:[28,85,88,168,176,179,181,183],Used:[32,33,34,35,36,37,50,85,87,106,109,112],Useful:[70,88],Uses:163,Using:[14,87,94,98,144,152,163,168,169,172,177,178,188],Will:[20,52,87,163],With:[14,18,28,170,184],Yes:[156,157,158,159,160,161],__cxa_throw:177,__gi_abort:177,__gi_rais:177,__n:177,__node:[177,178],_config:168,_costmap:[151,184],_from_numb:156,_joint:171,_link:171,_m_range_check:177,_nav:172,_to_numb:156,_twilio:156,abi:[94,143],abil:[6,7,28,94,153,185],abl:[0,5,9,14,19,20,152,153,156,157,159,160,161,163,166,168,169,170,172,177,178,186],abort:[151,157,177],about:[4,7,9,11,22,23,24,25,28,106,109,112,141,142,143,144,146,148,151,153,154,156,157,158,160,161,168,169,170,171,172,176,177,178,180,183,186],abov:[1,2,3,4,5,6,7,8,9,10,11,12,13,19,20,23,28,82,94,103,111,130,142,149,151,156,159,160,161,165,168,169,170,171,172,173,176,177,178,181,182,183,184,186,187],abrupt:28,abs:159,absolut:[47,48,93,112,150,159,168,171,177,181,183],absurdli:94,academ:6,acc_lim_i:[91,117],acc_lim_theta:[91,117],acc_lim_x:[91,117],accel:168,acceler:[84,97,98,104,117,152,168,172,187],accelwithcovariancestamp:168,accept:[6,61,83,103,129,130,146,161,165,166,179],acceptpendinggo:161,access:[0,28,143,144,151,152,157,169,171,177,186],accommod:143,accompani:88,accomplish:[8,156,163,168,171,177],accord:[28,93,168,169,181,183],accordingli:[9,87,181,183],account:[28,87,151,152,156,165,172,176],account_sid:156,accur:[6,28,87,151,168,172],accuraci:[26,87,149],achiev:[11,88,94,97,101,104,105,151,152,153,154,171,172],acircl:175,ackerman:165,ackermann:[101,148,151,163,165,172],ackermannconstrain:94,acknowledg:85,acquir:28,across:[18,28,94,100,108,129,130,143,153,161,164,169,170,172,186],act:[9,14,28,128,150,151,167,169,171,181,185,187],action:[11,17,19,27,30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,52,54,57,75,77,78,79,80,84,85,87,89,94,102,105,147,148,149,153,156,157,161,163,165,168,169,170,171,172,173,174,179,180,181,183,186],action_a:20,action_b:20,action_c:20,action_nam:157,action_typ:[87,185],actionnod:20,actionnodebas:157,actiont:161,activ:[12,27,28,58,71,72,73,87,92,141,146,147,150,151,152,153,156,159,160,161,168,169,172,173],actual:[19,52,87,88,94,98,152,161,166,170,171,172,175,180,185,187],actuat:143,adapt:[6,28,83,97,151,163,169,170,171],add:[0,2,8,17,74,75,76,77,78,79,80,81,82,88,94,109,110,114,143,146,150,151,152,153,154,156,161,166,168,169,170,171,172,173,174,177,178,182,184,185,186],add_act:[181,183],add_compile_opt:[177,178],added:[10,13,22,24,25,85,94,143,146,149,150,151,152,153,154,156,158,159,160,161,165,166,169,170,171,172,173,178,184,185,187],adding:[1,9,83,129,130,143,152,153,168,169,171,173,176,181,183],addit:[3,11,17,20,22,23,24,25,28,87,142,143,151,152,153,157,161,165,168,169,171,177,178],addition:[0,11,28,143,144,149,150,151,161],address:[32,33,34,35,36,37,41,42,45,149,150,151,152,153,154,156],adequ:172,adher:170,adjac:[103,107,176],adjust:[9,11,28,29,77,80,82,87,94,104,153,154,171,183,185],admiss:[129,130,152],admittedli:11,advanc:[0,28,164,172],advantag:[12,28,153,187],advic:[165,172],advis:[22,24,25,28,168],affect:[151,152,171],aforement:94,after:[2,10,21,22,24,25,27,28,83,85,87,94,98,99,104,113,115,122,127,128,129,130,146,147,151,152,158,159,160,161,166,168,169,171,172,173,175,176,177,178,179,181,183,184,186,187],afterward:168,again:[19,20,21,23,75,141,143,147,149,164,168,171],against:[58,71,72,73,130,153,172],agent:[87,172],aggreg:173,aggregation_typ:[132,133,136,137],aggress:87,agre:146,agreement:146,ahead:[84,94,97,119,120,132,136],aid:[2,23],aim:[1,7,9,10,13,104,167,171,172,178],aisl:[28,128,152,165,172],aislewai:152,aitor:163,alberto:163,aleksei:163,alexei:[14,148,163],alexeymerzlyakov:14,algorithm:[3,15,17,18,22,24,25,28,88,94,97,99,100,101,146,148,149,151,152,153,154,158,159,163,166,169,171,172,174,176,178],alias:28,align:[115,132,136,137,154],alik:14,aliv:14,all:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,17,18,19,20,27,28,39,74,83,84,87,92,94,97,99,101,103,104,107,111,134,142,143,144,146,148,149,150,151,152,156,159,160,161,163,165,168,169,170,171,172,173,174,175,177,178,181,183,184,186,187],allevi:172,alloc:[28,173,177,184],allot:[1,9,11],allow:[5,6,8,9,10,17,18,19,20,22,23,24,25,28,79,83,84,85,87,94,95,97,103,112,128,129,130,131,134,139,143,144,146,148,150,151,152,156,158,159,160,165,168,169,170,171,172,173,175,176,177,179,181,183],allow_revers:97,allow_reverse_expans:130,allow_unknown:[95,103,128,129,130,151,160],almost:[150,152],along:[14,27,28,56,66,82,94,97,98,106,109,112,129,130,134,150,151,152,153,163,165,169,171,173,174,177,181,183],alongsid:[161,172],alot:94,alpha1:83,alpha2:83,alpha3:83,alpha4:83,alpha5:83,alpha:[171,181],alreadi:[4,7,94,150,151,152,156,166,168,171,172,177],also:[1,3,4,6,7,11,17,19,20,21,22,23,24,25,27,28,83,84,86,87,89,90,92,93,94,97,99,101,102,105,129,130,142,143,144,146,147,148,149,150,151,152,153,154,156,157,158,159,160,161,165,166,168,169,170,171,172,173,174,175,176,177,178,181,182,183,184,185,187],alter:143,altern:[3,23,28,56,143,144,151,166,168,177],although:144,alwai:[9,16,21,70,87,92,104,130,141,151,152,171,172,181,187],always_on:[168,169],always_reset_initial_pos:83,always_send_full_costmap:[90,169],alwayson:169,ambigu:97,amcl:[6,7,17,27,28,29,50,63,147,148,150,163,169,170,172],amcl_pos:149,amclnod:152,amend:146,ament:[156,158,159,160,161,175],ament_cmak:[156,159,160,161,171],ament_cppcheck:146,ament_cpplint:146,ament_index_cpp:161,ament_index_python:[181,183],ament_uncrustifi:146,among:[17,28,103,165,172,176],amongst:171,amount:[90,111,121,123,125,127,128,129,130,139,150,151,153,181],ampl:[22,24,25],analog:[8,87,151,153,157,177,187],analysi:[7,28,146,148,178],analyt:[129,130,151,152],analytic_expansion_max_length:[129,130,152],analytic_expansion_ratio:[129,130],analyz:[5,6,7,10,27,28,157,178],andrei:163,angl:[27,28,54,87,103,121,128,129,151,163,172],angle_quantization_bin:129,angular:[56,87,94,97,98,116,117,120,129,132,135,136,138,153,159,168,172,187],angular_dist_threshold:[98,187],angular_distance_weight:56,angular_granular:[91,120],angular_limit:[87,153],angular_vel:159,angular_veloc:168,ani:[0,3,9,11,14,17,19,20,21,23,28,43,46,49,51,53,58,60,74,87,89,92,94,97,100,101,103,109,110,114,129,141,143,144,146,148,150,151,152,153,156,157,158,159,160,161,163,165,169,170,171,172,173,174,176,177,178,179,181,183,185,186,187],anim:[4,176],annot:[28,151,158,159,160,181,183],announc:146,anoth:[0,1,4,6,10,21,22,24,27,28,58,101,128,129,143,146,151,152,154,157,163,165,166,168,169,171,174,177,179,181,182,183,184],anshumaan:163,answer:[0,146,151],anybot:5,anyhow:152,anyon:11,anyth:[21,28,151,157,158,161,172,181,186],anywai:172,anywher:[144,152],apach:[1,2,3,4,5,6,7,8,9,10,11,12,13,146],apart:[23,187],apex:144,api:[18,28,52,148,149,151,156,158,161,169,174],appear:[87,146,147,151,152,153,169,171,175,176,180,185,186],append:[143,146,168,169],appli:[0,7,11,28,94,97,100,103,104,109,128,129,130,138,144,151,157,170,171,172,176,177,178,182,183],applic:[1,3,6,10,12,14,18,19,22,23,24,25,27,28,56,87,88,94,141,143,149,152,153,156,158,161,163,165,172,173,176,177,178,179,183,184,186,187],appreci:[28,146],approach:[23,28,79,87,94,95,97,101,103,128,129,130,148,151,153,154,163,165,168,172,174,185,187],approach_velocity_scaling_dist:97,appropri:[2,19,89,94,96,104,112,146,152,153,161,165,168,170,171,172,177,185,186],approv:[3,146],approxim:[87,98,104,128,147,153,165,166,172,175,187],apt:[142,143,147,168,169,171,175,178,182,184],arbitrari:[87,101,144,163,165,167,172],arbitrarili:148,arc:[87,169],architectur:[11,151],area:[3,7,28,38,39,87,90,106,109,111,112,128,129,130,146,151,152,153,156,158,163,169,171,172,175,178,181,183],areerrorcodespres:[86,153],arg:[142,175,177,178],argc:177,argument:[27,142,152,153,154,157,159,168,171,174,177,178,181,183],argv:177,arm:156,aroun:153,around:[9,14,19,23,28,38,56,79,87,88,90,94,97,108,146,148,151,163,169,170,171,172,175,182,187],arrai:[88,129],arriv:[105,126,151,163],arrow:[171,180],art:101,articl:[148,173],artifact:[99,101,143,176],artifici:94,as_str:161,asid:[168,169],ask:[0,3,28,146,158,177,186],asla:14,aspect:[20,143,144,174,175],assembl:186,assess:172,asset:177,assign:[28,52,56,88],assist:[0,27,30,146,163,172],assisted_teleop:[32,84],assisted_teleop_error_cod:30,assisted_teleop_serv:30,assistedteleop:[27,32,86,152,153,163],associ:[28,153,168,169,170],assum:[19,20,144,151,158,159,163,166,170,171,176,177,181,182,183,184,185,186],assumpt:[104,172,182],asymmetr:88,async_slam_toolbox_nod:169,asynchron:[19,20,28,150],ata:[126,163],atom:13,attach:[146,168,169,170,173],attempt:[1,19,21,22,24,25,28,79,92,93,94,100,128,129,130,144,154,177,181],attempt_respawn_reconnect:92,attent:[28,94,172],attest:146,attract:94,attribut:[94,153,181],auth_token:156,author:[144,146,148],auto:[143,159,161],auto_start:180,autom:[142,143,144],automat:[18,94,97,111,143,146,151,152,166,168,170,171,172,173,181,183],autonom:[1,27,28,94,97,148,151],autonomi:[1,27,28,149,152,153,173,186],autostart:[27,92,147,172,173,180,181,183],auxiliari:27,avail:[5,9,27,28,70,87,94,97,103,141,142,144,146,149,151,152,158,163,165,168,169,172,173,174,175,177,179,184],averag:[83,87,103],avoid:[1,28,87,88,90,94,109,130,143,148,151,152,158,165,166,168,169,170,171,172],awai:[21,88,94,98,128,153,169,175,186,187],awar:[22,24,25,88,94,101,103,129,130,151,169,172],awkward:[94,172],axes:104,axi:[27,104,158,171],back:[1,9,22,24,25,27,28,31,88,94,98,106,130,146,149,152,153,157,159,160,161,163,170,171,172,186],back_up:84,background:[93,150,152,171,172,181],backport:94,backtrac:[153,188],backup:[1,19,20,22,23,24,25,27,33,86,149,152,153,156,163],backup_dist:[19,22,23,24,25,27,31,86,151],backup_error_cod:31,backup_serv:[31,44],backup_spe:[19,22,23,24,25,27,31,86,151],backward:[56,115,135,138,151,153,177],backward_ro:177,bad:[22,24,25,28,83,156],bake:172,balanc:[94,100],ball:28,band:[3,149,165,187],bar:[171,175,186],barrier:14,base:[2,5,6,9,17,19,21,28,51,56,59,61,77,82,83,84,85,87,88,90,93,94,99,101,102,106,109,112,121,131,132,133,134,136,137,142,143,144,146,148,149,151,152,153,154,156,157,159,160,161,163,165,168,169,170,171,172,176,177,181,183,184,185,186],base_:171,base_class_typ:[156,158,159,160,161],base_footprint:[83,87,171,185],base_frame_id:[83,87,185],base_height:171,base_joint:171,base_las:170,base_laser2:170,base_length:171,base_link:[28,51,56,59,61,70,77,84,85,90,99,100,102,156,157,158,161,166,168,169,170,171,174],base_link_fram:168,base_shift_correct:87,base_width:171,baselin:[94,129,169],baseobstacl:91,baseobstaclecrit:91,bash:[141,142,143,147,158,166,168,169,171,180,181,182,183],bashrc:[141,143],basi:[5,94,172],basic:[4,5,17,18,19,27,28,130,149,151,152,158,161,165,166,167,168,169,170,177,184],basic_class_typ:158,basicnavig:[27,152],basket:27,batch:94,batch_siz:94,batteri:[19,20,28,64,65,152,153,163,179],battery_statu:[64,65],battery_top:[64,65],batteryst:[64,65],beam:83,beam_skip_dist:83,beam_skip_error_threshold:83,beam_skip_threshold:83,beamskip:83,beauti:177,becam:151,becaus:[23,28,92,94,143,144,146,151,156,168,170,172,177,178,180,186,187],becom:[4,11,18,19,28,92,94,103,149,152,168,170,171],been:[4,6,14,17,19,20,22,24,25,28,51,59,94,101,143,146,150,151,152,153,158,159,160,163,166,169,170,171,172,178,184,185],befor:[5,11,19,22,23,24,25,26,28,43,46,49,53,59,75,77,79,83,87,89,93,94,100,109,110,114,125,128,129,130,138,143,144,149,150,151,152,156,157,158,159,160,161,163,165,168,169,171,172,173,174,176,177,178,180,181,182,183,184,186,187],beforehand:11,begin:[129,130,152,159,161,168,171,173,187],beginn:[171,177],behalf:146,behav:152,behavior:[1,2,3,11,17,20,21,22,23,24,25,26,29,30,31,32,33,35,36,37,43,44,46,47,48,49,54,57,59,61,74,75,76,79,87,94,97,98,101,105,143,148,149,159,161,162,165,168,173,174,184,187,188],behavior_plugin:[84,152,156],behavior_serv:[84,92,152,156,173],behavior_tre:[19,27,47,48,85,150,154,161,186],behaviortre:[18,19,20,21,22,23,24,25,26,28,60,86,157,163,179,186],behaviortreenavig:[85,153,161],behaviour:[150,151,183],behavor:151,behind:[152,183],being:[0,6,8,11,19,22,24,25,28,54,87,88,93,94,106,112,129,130,143,150,151,154,159,161,165,166,168,169,172,173,177,181,183,185],believ:20,belong:[28,112,151,181,183],below:[0,4,9,11,13,16,18,19,20,23,27,28,65,82,85,89,91,94,98,99,101,103,105,110,111,114,124,139,146,148,151,152,153,156,157,158,159,160,161,163,166,168,169,170,171,173,174,175,176,177,178,179,180,181,183,185,186,187],belt:177,benchmark:[4,7,11],benefici:[2,28,94,109,161,177],benefit:[7,143,172],benign:144,berth:172,bespok:152,best:[6,8,11,28,29,87,94,115,128,129,130,143,146,152,153,165,169,170,172,176,177,181,184],better:[22,24,25,28,87,97,103,143,151,152,154,169,172,173,178,183,187],between:[14,19,27,28,83,86,87,94,95,97,99,103,128,129,130,143,144,148,150,151,152,153,154,155,161,165,166,168,169,170,171,172,181,186,187],bewar:153,beyond:[147,157,172,183],bezier:88,bias_mean:168,bias_stddev:168,bidirect:154,big:19,bin:[129,130,152],binari:[28,90,93,128,147,153,156,157,159,160,161,163,184],binary_filt:106,binary_st:106,binary_state_top:106,binaryfilt:106,bind:[88,161],bit:[19,152,172,177],black:[169,174,176,181],blackboard:[18,41,42,45,47,48,52,60,61,62,79,85,152,153,157,161,173,174,186],blacker:181,blanco:163,blank:160,blasco:163,blind:[97,151],blob:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],block:[12,13,27,28,141,152,158,160,168,171,172,184,187],blocki:130,blog:8,blue:186,bmp:[181,183],board:[28,175],bodi:157,bog:177,bogu:93,boiler:156,boilerpl:[156,161,167],bond:[92,150,169],bond_client_node_:152,bond_respawn_max_dur:92,bond_timeout:[92,151,173],bond_timeout_m:151,book:28,booktitl:148,bool:[52,54,83,85,87,88,90,92,94,95,97,99,100,103,104,105,106,107,108,109,110,111,112,113,114,115,118,120,122,125,126,127,128,129,130,131,134,151,156,161],both:[1,7,11,19,22,23,24,25,27,28,87,97,101,148,151,152,154,157,161,165,166,168,169,171,172,176,177,178,181,182,183,184,185,187],bottleneck:178,bottom:[147,166,169,175,177,178,180],bound:[9,56,87,97,100,128,129,130,152,158,185],boundari:[152,183],box:[1,9,28,87,105,152,153,166,168,169,171,172,184,185,186],box_inertia:[168,171],bpwilcox:14,branch:[5,13,23,129,130,141,142,143,146,152,174],breakdown:172,breakpoint:177,breez:171,breviti:[156,187],brian:[14,163],brief:[101,152,168,169,170,171],briefli:144,bring:[27,87,92,152,154,171,182],bringup:[27,28,92,142,147,152,153,158,165,167,169,172,173,185],bringup_launch:180,broad:[2,7,167,172],broadcast:168,broken:19,brother:156,brows:186,browser:[142,144],bsd:146,bt_action_server_:161,bt_loop_dur:85,bt_navig:[27,47,48,59,61,85,92,150,153,154,157,161,173],bt_plugin:[150,151],bt_register_nod:157,bt_xml_filenam:161,btactionnod:157,btstatu:161,budyakov:163,buffer:[28,84,102,104,110,114,156,159,160,184],bug:[14,146,164],buggi:186,build:[1,5,7,10,14,18,19,27,28,144,145,147,148,152,153,156,157,158,159,160,161,170,176,177,178,179,181,183,184,185],build_test:171,build_typ:[156,159,160,161],builder:[143,157],buildtool_depend:171,buildx:143,built:[11,143,146,158,166,167,168,169,171,175,176,177,181,182,183,184,185,187],builtin_interfac:173,bulldoz:28,bunch:141,burden:172,busi:28,button:[147,153,158,159,160,161,166,169,175,179,180],bypass:[87,181],c_str:[160,161],cach:[129,130,142,143,152],cache_obstacle_heurist:[129,130,172],cachefrom:143,calcul:[19,27,87,106,152,158,159,160,168,176],calendar:146,calib_cb_fast_check:175,calibr:[18,188],calibrationdata:175,call:[17,27,28,38,39,40,87,89,96,129,130,135,146,147,149,150,151,152,153,156,157,158,159,160,161,163,170,171,172,173,174,177,178,181],callabl:158,callback:[11,13,28,151,161],callback_group:152,caller:[22,24,25],callgrind:178,came:151,camera:[28,106,126,153,169,184,188],camera_calibr:175,camera_depth_fram:169,camera_depth_joint:169,camera_image_topic_nam:126,camera_joint:169,camera_link:[169,170],camera_nam:175,cameracalibr:175,can:[0,1,3,4,5,6,7,8,11,13,14,17,18,19,20,22,23,24,25,26,27,28,29,32,33,34,35,36,37,41,42,45,75,77,78,80,82,83,85,86,87,88,89,93,94,97,98,99,101,103,105,110,114,129,130,141,142,143,144,146,147,148,149,150,151,152,153,154,156,157,158,159,160,161,163,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],cancel:[17,21,23,27,32,33,34,35,36,37,147,157,161,163,179],cancelassistedteleop:[86,152],cancelbackup:86,cancelcontrol:[23,86,152],canceldriveonhead:86,cancelingcontrolandwait:23,cancelnav:152,cancelspin:86,canceltask:27,cancelwait:86,candid:[1,7,94,146,165],cannot:[28,70,94,97,104,129,130,135,151,153,161,173,184,186],canon:28,capabl:[4,7,10,15,27,143,144,148,151,164,169,179,187],captur:[28,152,165,178],car:[101,148,151,163,166,172],care:94,career:11,carefulli:165,carl:[14,163],carlo:[6,28,83,169],carri:[28,150,151,152,160,179],carrot:21,cart:4,cartesian:94,cartograph:149,cast:7,caster:171,caster_joint:171,caster_xoff:171,catchi:8,categori:165,cater:152,cati:179,caus:[23,31,44,83,87,94,129,130,147,152,172,176,181,183],caution:[144,176],ccach:[142,143],ccw:26,ceas:87,cell:[27,28,103,107,108,110,111,114,152,158,165,166,169,171,176,181,183],center:[19,28,38,39,94,109,128,129,130,152,156,166,170,171,175,180],central:28,cerescostawaresmooth:[102,174],certain:[20,150,152,158,165,167,169,179],certif:[87,145],certifi:[9,87,146],chain:183,challeng:28,chanc:[1,7,9,20,152],chang:[6,11,12,13,14,17,18,19,22,24,25,27,28,60,62,74,87,88,94,100,104,122,128,129,130,132,136,143,146,147,150,158,159,161,164,166,168,169,172,177,179,180,181,183,184,186],change_penalti:[129,130],changemap:27,channel:146,chao:146,chapter:[28,181,183],charact:99,characterist:[4,12,100,168],charg:[28,64,153,163,165],charger:28,charuco:175,chassi:[170,171],chat:146,check:[0,7,9,11,14,19,20,23,27,28,51,52,58,60,61,62,64,65,66,68,70,71,72,73,79,84,85,86,88,89,90,94,97,98,102,105,109,121,122,123,124,135,141,142,143,144,146,148,150,151,152,156,157,158,159,160,161,163,165,166,168,169,170,172,175,176,177,180,181,183,187],check_for_collis:[27,52],checker:[18,45,89,115,149,156,187],checkerboard:175,checklist:167,checkout:[97,142],chessboard:175,child:[19,20,23,70,74,75,77,80,81,82,152,163,168,169,170,171],child_frame_id:168,children:[19,20,23,74,75,76,79,163,178],chip:172,choic:[10,27,28,172,173,182],choos:[103,143,144,147,161,166,170,172,176,177,183],chosen:[27,28,143,153,183],christoph:163,chronicl:143,chug:177,cilqr:3,circl:[20,87,172,175,185],circular:[94,101,148,154,165,166,171,172],cite:[97,148],citizen:184,cla:[1,2,3,4,5,6,7,8,9,10,11,12,13],claim:146,class_list_macro:[156,158,159,160,161],classic:172,classification2d:169,classification3d:169,clavero:148,clean:[28,94,143,150,152,156,159,160,161,172],cleaner:171,cleaningup:173,cleanli:[28,92,161,172,178],cleanup:[156,159,160,161,173],clear:[19,20,22,23,24,25,27,28,38,39,40,90,110,111,114,146,151,152,153,160,163,169,175,184],clear_after_read:184,clear_around_:151,clear_around_local_costmap:38,clear_entirely_global_costmap:[19,22,23,24,25,86,157],clear_entirely_local_costmap:[19,22,23,24,25,40,86,157],clear_except_:151,clear_except_local_costmap:39,clear_on_max_read:[111,169],clear_threshold:111,clearallcostmap:27,cleararoundrobot:152,clearcostmaparoundrobot:86,clearcostmapexceptregion:86,clearcostmapservic:20,clearentirecostmap:[19,22,23,24,25,86,151,157],clearer:169,clearexceptregion:152,clearglobalcostmap:[19,22,23,24,25,27,86,157],clearing_endpoint:151,clearingact:[19,22,23,24,25,86],clearlocalcostmap:[19,20,22,23,24,25,27,38,39,40,86,157],clever:177,cli:[28,93,143,144,150,151,178,182],click:[16,144,147,158,159,160,161,166,169,175,180,186],clicked_point:179,clicked_point_to_pos:179,client:[20,28,149,151,152,156,157,161,174],client_nod:152,client_node_:152,clinet_node_:152,clip:[169,181],clock:[181,183],clock_:[159,161],clone:[142,175,179,181,182,183,184],cloned_tb3_simulation_launch:154,close:[23,28,51,79,87,90,94,97,104,130,133,139,143,151,152,159,166,172,185],closed_loop:104,closer:[55,94,129,153],closest:[56,97,115],cloud:[7,28,143,144,147,150],cmake:[156,158,159,160,161,175,178],cmake_build_typ:178,cmakelist:[156,158,159,160,161,168,169,171,177,178],cmd:[168,169],cmd_vel:[13,87,159,168,178,185],cmd_vel_in_top:[87,185],cmd_vel_nav:178,cmd_vel_out_top:[87,185],cmd_vel_raw:[87,185],cmd_vel_teleop:84,code:[5,6,15,30,31,41,42,44,45,47,48,52,54,58,71,72,73,83,84,85,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,104,105,143,144,146,149,150,152,156,157,158,159,160,161,163,166,168,169,171,174,176,177,184,187],codebas:146,codecov:12,codespac:[143,144],codifi:143,coeffici:[112,175,181,183],coffe:[144,186],colcon:[142,143,158,166,168,169,171,177,178,181,183],collabor:[4,14,146],collect:[27,167,169,178],collid:[4,9,166],collis:[1,7,9,28,29,30,52,84,88,90,94,97,98,102,109,139,148,149,151,152,156,163,164,165,166,168,169,171,172,187,188],collision_cost:94,collision_margin_dist:94,collision_monitor:[87,185],collision_monitor_nod:185,collision_monitor_param:185,collision_monitor_st:87,collisionmonitor:153,color:[8,88,126,169,171,172,176,181,183,184],color_dark:181,color_light:181,column:[114,169],com:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],combin:[28,90,132,133,136,137,151,182],combination_method:[90,110,114,154,184],come:[8,13,14,28,94,97,124,146,152,153,156,159,160,161,168,170,171,185],command:[1,9,17,23,30,43,46,49,53,78,97,98,104,142,143,144,148,150,156,158,159,160,161,163,165,168,169,170,171,177,179,180,181,182,183,187],commandlin:[93,177,178],comment:[143,146,152,158,160,177,184],commerci:[28,146],commit:[143,146,164,175],common:[19,27,28,94,143,144,148,151,152,161,168],commonli:[20,43,46,49,53,161,169],commun:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,17,28,143,146,148,156,161,170,172,173,175],compani:[146,148,172],companion:186,compar:[28,58,71,72,73,85,88,101,153],comparison:[14,148],compat:168,compet:146,compil:[143,144,156,159,160,161,174,177,178],complement:[5,150],complementari:173,complet:[3,4,5,12,17,19,20,23,27,28,52,87,94,97,98,122,129,130,139,143,146,147,148,149,150,151,152,153,154,156,157,161,164,165,166,168,169,171,173,174,175,178,180,182,184,186,187],complex:[17,28,85,94,148,153,169,170,171,177,186],complexyolo:4,compli:[2,165,168],complianc:104,compliant:170,complic:148,complimentari:161,compon:[6,17,74,75,76,77,78,79,80,81,82,103,104,138,151,152,167,171,173,181,183],component_contain:173,component_container_isol:152,componentcontain:177,compos:[11,152,158,172,173,177,178],composable_node_descript:173,composablenod:[173,185],composablenodecontain:173,composit:[164,177,178],composition_demo:173,comprehens:143,compris:[13,171],comput:[7,17,18,19,20,21,22,28,41,42,94,96,97,101,103,128,129,130,132,136,148,152,153,156,157,159,160,163,165,166,168,169,170,172,174,178,180],computation:[28,114,152],compute_path_error_cod:[41,42,85,174],compute_path_error_code_id:173,compute_path_through_pos:[153,173],compute_path_to_pos:[153,173],compute_path_to_pose_error_cod:72,computeandpublishveloc:151,computeandsmoothpath:174,computepaththroughpos:[22,86],computepaththroughposesrecoveryfallback:22,computepathtopos:[18,19,20,21,23,24,25,49,51,77,80,82,86,157,161,174,179],computepathtoposeact:49,computepathtoposerecoveryfallback:[19,24,86],computevelocitycommand:[89,159],concaten:151,concept:[7,19,20,148,151,165,169,170,173,181,183,186],conceptu:170,concern:[144,146,152],conclus:23,concret:170,condit:[12,19,22,24,25,28,30,31,44,54,66,67,70,100,143,152,153,157,163,168,171,186,187],conditionnod:157,conf:157,confer:148,config:[143,144,166,168,169,171,177,182],configur:[0,1,14,16,17,18,19,20,27,28,43,46,49,53,59,87,88,89,90,92,93,94,101,106,109,112,142,143,144,149,150,152,153,154,156,157,159,160,161,163,167,171,172,173,174,176,177,179,180,182,184,186],configured_param:[173,181,183,185],confin:[94,143,154,166],confirm:[166,169,175],conflict:150,conform:148,confus:20,conjunct:[27,94],connect:[14,20,28,92,95,103,107,128,143,144,150,151,152,163,165,168,169,170,171,176,186],consequ:23,consid:[3,14,19,30,31,44,54,83,85,86,87,90,94,124,129,130,139,146,150,151,153,156,157,159,160,161,163,165,172,173,181],consider:[4,94,172],consider_footprint:94,consist:[8,18,144,146,151,152,163,168,169,170,172,173,186],consol:185,constant:[20,97,159,171,172],constantli:[150,152],constrain:[29,100,151,163,172],constrainedsmooth:[88,152],constraint:[22,98,104,151,152,161,163,165,172,187],constraintcrit:94,construct:[28,146,152],constructor:[28,152,157],constsharedptr:161,consult:14,consum:[9,152],contact:[1,2,3,4,5,6,7,8,9,10,11,12,13,146,148,172,173],contain:[9,11,18,22,24,25,28,45,48,94,101,104,130,145,149,150,151,152,153,154,156,158,159,160,161,163,168,169,171,172,173,174,175,177,181,185,187],container:143,containeris:143,content:[144,166,167,169,171],context:[11,13,19,20,22,23,24,25,86,142,157,163,186],contextu:[18,19,22,24,25,148,153],continu:[1,12,19,20,21,22,23,24,25,28,94,105,127,129,130,144,146,147,148,149,150,151,152,153,161,168,171,172,182],contractor:14,contrast:152,contribut:[1,2,3,4,5,6,7,8,9,10,11,12,13,28,146,169,172,173],contributor:[14,146],control:[2,4,7,9,11,13,17,18,19,21,22,23,24,25,27,29,34,43,45,55,56,71,72,73,75,76,77,78,82,87,90,97,101,104,112,116,117,118,119,120,121,122,123,124,130,131,132,133,134,135,136,137,138,139,140,148,149,150,154,156,157,158,161,162,164,167,168,171,173,174,177,178,179,180,182,183,184,185,186,188],controlcancel:23,controller_frequ:[89,91,94,97,98,187],controller_id:[19,21,22,23,24,25,27,43,45,86,151,157,179],controller_pati:151,controller_plugin:[89,91,97,98,150,159,165,187],controller_plugin_id:[115,116,117,118,119,120,131,132,133,134,135,138,139,140],controller_selector:43,controller_serv:[23,89,91,92,94,97,98,150,151,152,159,165,173,178,183,185,187],controllerselector:[22,24,25,86,151],controllerserv:[152,185],controlnod:157,conveni:[144,183],convent:[22,24,25,28,169,170,173],converg:[83,88,94],convers:[27,93,146,181,183],convert:[0,94,112,129,130,148,149,151,160,170,181,183],convert_typ:[181,183],convex:94,cooper:2,coordin:[5,27,28,83,90,152,168,170,171,179],copi:[152,166,168,169,171,174,177,181,183,184],copyright:146,core:[7,18,28,148,153,173,174],corner:[97,147,151,175,181,186],corpor:14,correct:[28,87,141,143,146,152,168,169,171,180,181,183,185],correctli:[20,28,147,151,152,166,168,169,170,181,183,185],correl:143,correspond:[28,79,85,87,94,95,103,106,107,108,109,110,111,112,113,114,128,129,130,151,152,156,157,158,169,170,176,183],correspont:181,corridor:[94,165,172],cost:[9,19,27,28,84,87,88,90,94,97,101,103,109,118,128,129,130,143,151,152,158,163,169,172,176],cost_check_point:88,cost_cloud:151,cost_penalti:[129,130],cost_pow:94,cost_scaling_factor:[90,94,103,108,158,169],cost_travel_multipli:128,cost_weight:94,costamp2d:181,costli:28,costmap2d:[141,162,163,176,181,183],costmap2dro:[152,159],costmap:[1,2,4,5,7,10,19,20,21,22,24,25,29,38,39,40,84,87,88,97,102,103,106,108,109,110,112,114,128,129,130,131,134,148,149,152,158,159,160,165,166,172,176,188],costmap_2d:[5,17,158,169],costmap_2d_cloud:151,costmap_2d_ro:113,costmap_:[158,160],costmap_filter_info:[93,106,109,112,181,183],costmap_filter_info_serv:[93,181,183],costmap_filters_demo_dir:[181,183],costmap_raw:[84,99,100,102,156,174],costmap_ro:[152,159,160],costmap_ros_:159,costmap_top:[99,100,102,156,174],costmapfilt:151,costmapfilterinfo:[106,109,112,181,183],costmapinfotyp:153,could:[1,2,3,6,7,9,10,21,28,87,89,103,143,144,150,151,152,153,157,158,159,163,170,172,174,177,179,181,183,184,185],couldn:177,count:[94,152,168,175,181],counter:[30,101,152,157,161,168],counterpart:172,coupl:[27,187],cours:[5,11,143,171],covari:83,cover:[2,28,111,146,151,165,172,173,177,181,183],coverag:[3,4,6,12,28,161,164],cpp:[19,28,149,150,151,152,157,158,163,177,186],cpu:[4,7,87,143,152,172,173],crash:[28,92,150,152,172,173,186],crdelsei:14,creat:[1,4,5,6,8,9,10,11,13,14,22,23,24,25,28,41,42,76,79,87,90,92,94,100,101,142,144,146,148,149,150,151,152,153,158,163,165,166,168,169,170,171,172,173,176,180,181,183,184,185,186,187],create_cli:161,create_subscript:161,createplan:160,creation:[9,150,172],creativ:[6,8],creator:163,criteria:[28,122,139,146,152,163],criterion:88,critic:[1,7,9,28,115,131,132,133,134,135,136,137,138,139,140,149,165,172,173,177],critical_weight:94,cross:[141,143,148,165,166],crowd:[22,24,25,165],crtl:[143,144],crux:19,ctrl:143,cube:[166,169],cubic:88,cuda:7,cull:[22,51,163],current:[3,9,11,12,14,19,20,25,27,28,44,51,56,60,77,80,82,87,94,96,97,98,104,105,106,109,111,112,130,146,148,150,151,152,153,156,157,159,160,161,163,168,169,170,171,172,173,179,185,186,187],current_path:161,current_pos:161,curv:[103,158,172],curvatur:[94,97,129,151,159,165],curvature_lookahead_dist:[97,153],curvature_smooth:[102,174],cusp:[88,94,97],cusp_zone_length:88,custom:[10,18,19,20,22,24,25,27,28,55,56,76,78,83,84,85,94,101,105,130,142,143,144,148,152,153,156,159,160,161,163,165,167,169,184],customiz:153,cut:[129,130],cxprime:169,cyan:[88,171],cycl:[23,87,97,129,130,152,156],cycle_frequ:[84,156],cylind:[169,171],cylinder_inertia:171,dai:11,damag:104,danger:[88,148,185],dark:181,darker:183,dash:147,data:[1,4,7,9,10,27,28,85,87,94,100,110,111,114,128,129,130,143,148,151,153,163,168,169,170,173,175,178,181,183,184,185],data_typ:[90,110,114,169,184],date:[83,87,106,109,112,146,149],david:[14,91,163],dcmake_build_typ:178,dco:145,deactiv:[28,92,156,159,160,161,173],dead:28,deadband:[104,152],deadband_veloc:104,deal:[7,28,168,170,172],dealloc:28,dealt:19,debug:[28,88,94,114,115,118,129,143,153,177,178],debug_optim:88,debug_trajectory_detail:[91,115,159],debug_visu:[129,154],debugg:[143,177],debuggin:94,decad:[6,14],decai:[83,94,108,163,169],decay_acceler:184,decay_model:184,decel_lim_i:[91,117],decel_lim_theta:[91,117],decel_lim_x:[91,117],deceler:[117,154],decemb:[101,172,184],decent:94,decid:[23,83,154,170,171,173],decis:166,declar:[59,61,143,146,151,156,158,159,160,181,183],declare_autostart_cmd:[181,183],declare_mask_yaml_file_cmd:[181,183],declare_namespace_cmd:[181,183],declare_paramet:161,declare_parameter_if_not_declar:[159,160],declare_params_file_cmd:[181,183],declare_use_sim_time_cmd:[181,183],declarelaunchargu:[168,171,181,183],declareparamet:158,decod:183,decor:[19,21,23,152,157,163,179,186],decoratornod:157,decreas:[94,153,184,185],decrement:158,dedic:14,deduc:177,deeper:[94,169],deepli:186,def:[152,171,181,183],default_bt_xml_filenam:[85,150,157,161,179],default_control:43,default_critic_namespac:115,default_goal_check:46,default_model_path:171,default_nav_through_poses_bt_xml:[85,161],default_nav_to_pose_bt_xml:[85,154,161],default_plann:49,default_rviz_config_path:171,default_server_timeout:85,default_smooth:53,default_st:106,default_valu:[168,171,181,183],defaultsto:168,defin:[1,5,9,10,19,27,28,43,46,49,53,58,59,61,79,84,85,87,89,90,93,94,96,102,105,115,116,117,118,119,120,121,122,123,124,125,126,127,131,132,133,134,135,136,137,138,139,140,143,149,150,151,152,153,157,158,160,161,165,166,168,169,170,171,173,176,177,180,181,183,184,186],definit:[28,45,52,85,153,156,158,161,168,169,171,173],deg:94,degrad:129,degre:[11,26,87,129,151,154],delai:87,delet:[152,168],deliv:27,deliveri:1,deloc:50,delsei:[14,163],delta:103,demand:[28,159,160],demo:[8,10,23,28,152,166,173,181,183],demo_inspect:27,demo_pick:27,demo_secur:27,demonstr:[4,10,27,142,152,158,184,185],deni:161,denois:[90,163],denoise_lay:[107,176],denoiselay:[107,176],denot:[169,177],dens:27,dense_qr:88,densiti:[83,94],depend:[19,28,87,94,112,142,143,144,149,151,152,153,154,156,157,159,160,161,165,166,168,171,172,176,177,180,181,185],depict:[23,88],deploi:[4,94,165],deploy:[151,173],deprec:[6,88,151,152],depth:[28,87,163,165,169,170,171,184],depth_camera:169,depth_camera_control:169,deriv:[87,144,156,158,168,171],descent:[99,152],describ:[19,20,94,146,147,154,158,159,160,161,165,168,171,177,178,183,184,185,186],descriopt:106,descript:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,27,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,69,70,71,72,73,75,77,78,79,80,82,83,84,85,87,88,89,90,92,93,94,95,96,97,98,99,100,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,150,151,156,157,158,159,160,161,163,165,168,171,172,181,183],descriptor:170,design:[5,6,8,27,28,94,99,101,151,153,158,172,176,181,183,185,186],desir:[87,94,97,126,143,146,151,153,154,159,172,179,183],desired_linear_vel:[97,159],desired_linear_vel_:159,desk:148,destin:[27,28,61,147,168,169,171],destroi:143,destroynod:27,detail:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,20,28,85,94,101,106,109,112,143,146,150,151,152,153,156,158,159,160,161,165,166,167,168,170,172,177,183,184,186],detect:[4,28,52,56,87,88,97,143,166,168,169,175,179],detection2d:169,detection3d:169,detector:[28,179],detectron2:4,determin:[0,67,105,115,126,161,165,171,176,177,178],determinist:[11,28,92,99,173],dev:[142,145],devcontain:[143,144],devcontainerid:143,devel:[182,184],develop:[3,4,5,8,11,14,22,24,25,28,101,103,141,143,144,152,164,171,172,173,177,187],developercertif:146,dever:143,deviat:[83,94,104,154,172],devic:143,diademata:147,diagnost:168,diagnostic_msg:168,diagnosticarrai:168,diagon:107,diagram:[148,170,179],diamet:168,dictat:187,did:[20,21,156,159,160,169,171,177,178],didn:172,diego:14,diff:[88,101,163,172],diff_driv:168,diff_drive_control:168,diffdriv:94,differ:[10,18,19,20,22,23,24,25,28,60,86,87,97,98,101,103,106,109,112,143,144,146,148,150,152,153,158,161,165,167,168,169,170,171,172,173,174,177,179,181,183,186,187],differenti:[8,83,94,98,101,103,148,151,152,163,165,166,168,169,171,172,187],differentialmotionmodel:83,difficult:[28,98,152,172,187],difficulti:[1,2,3,4,5,6,7,8,9,10,11,12,13],digit:[99,126,163],dijkstra:[3,95,152,163,165],dilig:144,dime:172,dimens:[151,171,175],direct:[4,56,88,94,97,101,104,116,129,130,135,142,143,151,154,164,165,170,175,180,185],directli:[94,127,143,144,146,151,157,158,171,177,181,183],directori:[126,142,143,144,151,152,156,158,159,160,161,163,166,168,169,171,172,181,183],disabl:[83,87,89,128,129,130,152,153,175],disable_calib_cb_fast_check:175,disagre:83,disappear:87,discard:[107,152,176],discontinu:[99,101,130],discours:[0,146],discov:[142,157],discover:[156,158,159,160,161],discoveri:[92,143],discret:[28,143,146,165,168],discretize_by_tim:120,discuss:[3,6,20,28,146,150,151,152,159,160,165,166,167,168,169,170,171,173,187],dislpai:169,dispatch:28,displac:[31,44],displai:[2,96,129,151,166,168,169,171,172,176,183,186],disproportion:94,disscuss:151,dist:[129,130,175],dist_to_travel:[26,44],distanc:[18,20,21,27,28,31,44,54,55,56,59,61,77,83,84,88,94,97,98,115,120,129,130,135,149,150,151,159,163,165,168,169,170,172,179,187],distance_backward:56,distance_forward:56,distance_remain:[151,161],distancecontrol:[18,19,86,88,150],distancetravel:86,distancetraveledcondit:150,distant:56,distinct:[28,170],distort:[99,175,176],distortionk1:169,distortionk2:169,distortionk3:169,distortiont1:169,distortiont2:169,distribut:[94,141,143,144,146,147,155,164,181],distro:[141,142,147,168,169,171,175,180,182,184],distroa:141,distrob:141,dive:171,diverg:[129,130,172],divid:[150,151],do_beamskip:83,do_refin:[99,100,102,129,130,153,174],doc:[8,142,147,150],dock:[18,19,28,165],docker:[143,144],dockerfil:[142,143],document:[8,10,15,19,23,28,142,143,146,147,150,168,169,170,171,176,177,178,181,182,183],doe:[4,9,20,22,23,24,25,87,94,109,111,129,130,143,151,152,153,156,159,160,161,166,168,172,173,174,181,183,186],doesn:[74,128,151,152,156,172,181],doing:[27,105,109,146,161,177],doisi:163,domin:[110,114,154],don:[129,130,134,147,151,170,172,174,177,179,180,181,182],done:[13,19,20,28,87,143,149,150,151,158,159,160,161,164,165,169,177,178,186],dont:171,door:18,doubl:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,51,52,54,55,56,57,59,61,69,77,79,80,82,83,84,85,87,88,89,90,92,93,94,95,96,97,98,100,102,103,104,106,108,109,110,111,112,113,114,115,117,118,119,120,121,122,123,124,125,128,129,130,131,132,133,134,135,136,137,138,139,140,151,159,160],doubt:94,down:[27,28,92,94,97,103,112,147,150,152,153,172,173,177,183,185],download:[5,143,175],downsampl:[88,94,128,129,130,152],downsample_costmap:[128,129],downsample_factor:[128,129],downsampling_factor:[128,129],downstream:151,doxygen:145,dozen:28,drag:[147,186],dramat:[129,130,150],draw:[181,183],drawn:181,drift:[28,168],drivabl:[98,165,172,187],drive:[1,26,27,35,44,88,94,97,101,129,130,148,151,159,163,165,166,168,169,171,172,181],drive_on_head:[35,84],drive_on_heading_error_cod:44,driven:[4,172],driveonhead:[26,86,153],driver:[1,13,16,141,143,168,169,175],drivetrain:163,drivewhl_l:171,drivewhl_l_joint:168,drivewhl_r:171,drivewhl_r_joint:168,drop:[9,150,186],dropdown:2,dual:144,dub:152,dubin:[129,130,151,152,163,165],dubiou:152,due:[0,6,9,11,23,28,32,33,35,36,37,83,94,104,129,130,146,150,151,152,153,161,168,169,172,176,186,187],dumb:28,dummi:158,dump:165,duplic:[28,161],durabl:171,durat:[52,69,82,84,85,89,92,94,135,146,152,157,159,173,179],dure:[6,23,87,88,92,94,129,130,143,150,151,152,153,157,158,166,171,172,178,180,182,186],dwa:[3,17,163,165],dwb:[1,3,9,17,22,24,25,28,29,116,117,118,119,120,131,132,133,134,135,136,137,138,139,140,149,150,163,165,172,187],dwb_core:[89,91,150,151,165,187],dwb_critic:[91,115],dwb_local_plann:150,dwb_plugin:[91,115],dwblocalplann:[89,91,150,165,187],dynam:[0,3,13,15,18,22,24,25,28,78,79,87,94,129,130,148,149,150,151,156,157,158,159,160,161,164,165,169,171,172,183,184,185,186,188],dynamicfollowpath:150,each:[11,17,19,22,24,25,26,27,28,60,83,84,85,87,89,90,94,96,102,104,127,144,146,148,149,151,152,153,156,157,158,159,160,165,168,169,170,171,172,173,174,176,177,181,183,186],earli:[5,11,16],earlier:[83,129,130,144,147,152,156,170],easi:[10,11,14,19,28,143,144,146,167,169,182],easier:[146,165,169,170,171,172,177,187],easili:[13,19,28,85,143,150,151,152,154,172,178,185],ecosystem:[0,28,101,152,172],edg:[4,94,170,181],edit:[8,151,163,168,169,174],editor:[181,183,186],educ:14,effect:[2,4,87,88,111,128,143,150,152,168,181],effici:[23,28,101,169,172,173],effort:[8,14,28,104,146,148,151,165,169,172,184],efk:168,eight:176,eitan:163,either:[1,19,20,27,83,87,93,94,111,143,144,153,154,163,165,168,169,178,183,186],ekf:168,ekf_filter_nod:168,ekf_localization_nod:168,ekf_nod:168,elaps:151,elast:[3,149,165,187],element:[8,149,156,168,171],elev:[18,28,144,146],elif:[27,152],elimin:171,elong:88,eloqu:28,els:[27,90,151,152,158,159,161,168,185],elsewher:178,email:[0,14,28,146],emb:170,embed:[6,28,152,172,173],emerg:[6,9,87],emit:169,emploi:87,empti:[41,42,110,113,114,125,150,151,152,159,161,176],emul:143,emulate_tti:[181,183],enabl:[10,13,23,51,83,87,90,94,97,105,106,107,108,109,110,111,112,113,114,125,126,127,130,143,144,148,151,152,153,154,156,159,160,161,163,168,169,171,172,173,182,184,185,186],enabled_:158,enact:[9,79,187],encod:[28,106,112,168,170,181,183],encompass:172,encount:[16,165,169,177,178],encourag:[0,14,23,94,146,171,173,177],end:[6,11,21,28,87,94,95,99,128,152,154,156,158,159,160,161,163,171,172,173,176,177],endpoint:[129,130],energi:[94,169],enforc:[88,104,109,151,175],enforce_path_invers:[94,154],engag:146,engin:[6,142,144,149,178],enhanc:146,enough:[19,153,166,175],enrich:144,ensur:[4,9,11,13,21,22,24,25,28,92,94,97,143,144,146,149,151,152,153,165,166,170,171,172,173,178,184],enter:[22,24,25,28,94,156,159,160,161,181],entir:[12,19,20,22,24,25,142,143,146,163,165,172],entiti:168,entri:[14,168,174,177,178],entryfil:172,entrypoint:142,enumer:[30,31,41,42,44,45,52,54,186],env:143,environ:[4,5,9,10,12,28,101,141,142,143,144,146,147,148,165,166,168,169,170,172,180,181,185],environemnt:169,environment:[90,148],envok:[30,31,44,54],envrion:184,ephemer:143,eppstein:163,eqal:88,equal:[28,87,106,158,175,176,181,183],equat:103,equip:[169,186],eros:176,error:[28,30,31,41,42,44,45,47,48,52,54,58,71,72,73,83,85,87,141,150,151,152,163,166,169,174,176,180,184],error_cod:[58,71,72,73,173,174],error_code_id:[30,31,41,42,44,45,47,48,52,54,174],error_code_id_nam:[153,173],error_code_nam:[47,48,85],error_codes_to_check:58,especi:[83,129,130,144,149,152,170,174,180,182,184,187],essenc:170,essenti:[6,129,130,152,169,172],establish:173,estim:[15,83,87,99,104,147,149,151,158,159,160,161,168,169,170,180],estimated_time_remain:[151,161],etc:[4,10,13,18,27,28,85,87,106,143,144,146,151,153,156,161,165,167,168,170,172,182,186],eth:5,euclidean:[151,172],evalu:[115,118,130,165],evalul:7,even:[20,21,22,24,93,94,97,104,129,144,150,151,152,163,165,166,167,168,172,177,181],evenli:83,event:[1,13,146,152],eventu:[153,169,171],ever:[94,151],everi:[18,20,22,24,25,56,81,88,90,94,97,110,114,146,151,152,157,158],everyon:[144,146],everyth:[147,152,158,168],everywher:[94,149],exact:[94,99,128,129,130,143,153,165,166,172,179,181],exactli:[128,147,172,183],exampl:[1,7,15,16,17,18,19,20,23,28,101,142,143,144,150,151,152,154,156,157,158,159,160,161,166,167,168,169,170,171,172,173,174,175,176,177,178,181,183,184,186,187],example_assisted_teleop:27,example_follow_path:27,example_nav_through_pos:27,example_nav_to_pos:27,example_rout:27,example_waypoint_follow:27,exce:[30,31,44,54,112,151],exceed:[19,153],excel:[1,7,9,187],except:[27,28,39,89,146,151,153,160,163,168,177,183],exception:[161,168,178],excess:11,exchang:94,exclud:153,exclus:23,exe:177,exec:143,exec_depend:[168,171,173],execut:[10,11,17,19,21,22,24,25,27,75,79,85,98,105,143,144,146,150,151,152,157,158,161,163,165,166,168,169,170,171,173,176,177,178,181,183,186],executeprocess:[168,169],executor:[11,27,28,105,151,153],exemplari:18,exhaust:164,exhibit:23,exist:[4,8,11,12,17,28,87,93,94,128,141,143,146,150,151,152,154,159,161,172,178,179,186],exit:[22,24,28,92,150,152,177,178],expand:[95,129,130,131,143,152,165,171],expans:[8,95,103,129,130,151,152,153,163],expect:[5,11,27,83,94,96,110,114,146,148,150,151,161,168,173,174],expected_planner_frequ:[96,103],expected_update_r:[110,114,184],expend:172,expens:[28,114,152,153,168],experi:[1,2,3,4,5,6,7,9,10,12,26,142,143,144,148,152,171,177,180],experienc:167,expert:[4,14],expir:[23,68,163,184],explain:[11,19,20,23,144,146,166,177,178,182,187],explan:[19,101],explicitli:[4,27,144,181],explor:[169,170],exponenti:[83,94,108,163,169],expos:[20,28,102,151,153],exposur:7,express:[112,159,181,183],extend:[158,168],extens:[23,28,94,143,144,153],extent:97,extern:[4,22,24,25,27,89,92,125,142,143,149,150,153,173,188],extra:[88,129,130,152,181],extract:[152,161,163],extrem:[2,19,109,151,169],facilit:[144,152],factor:[79,88,94,108,128,129,139,169,172],factori:157,fail:[19,20,22,24,25,27,28,89,92,105,128,129,130,149,151,152,153,156,161,163,177],failed_to_make_progress:[71,153],failed_to_smooth_path:[73,153],failur:[1,18,19,20,21,22,24,25,28,30,31,44,54,58,60,61,62,64,65,66,67,68,70,71,72,73,74,75,81,94,148,149,151,152,157,163,173,177,179],failure_toler:89,fair:8,fairli:177,faith:146,fake:28,fall:87,fallback:[22,24,25],fals:[26,27,30,52,65,83,85,87,88,90,92,94,95,97,103,104,105,106,108,110,111,112,113,114,115,118,120,128,129,130,131,134,147,151,152,153,156,158,160,161,168,169,172,176,177,180,181,184,185,186],familiar:[19,28,171],fanci:143,far:[87,94,129,130,147,152,154,169,172,179,187],farm:184,fashion:20,fast:[83,87,99,100,129,130,152,176],faster:[152,172],fault:[12,27,28],favor:152,favourit:[181,183],feasibl:[28,94,98,100,101,109,148,151,152,154,163,165,172,187],featur:[1,4,6,8,9,14,28,83,97,100,143,146,147,151,152,163,164,171,181],feaur:181,feed:173,feedback:[14,27,28,85,104,146,152,161],feedback_msg:161,feel:[6,141,144,171,172],ferguson:[14,148],fetch:[159,160],fetullah:163,few:[4,11,14,20,27,79,88,142,143,165,169,172,177],field:[4,83,87,112,128,150,151,152,153,156,158,160,161,168,169,171,173,175,177,181,183,184],figur:186,file:[1,2,17,18,28,84,85,87,92,93,103,126,141,142,143,144,146,147,148,150,151,152,157,158,163,166,170,171,172,173,174,175,179,180,181,182,183,184,185,186],filenam:[168,169],filepath:[130,161,172],filesystem:[144,177],fill:[4,146,150,157,175,181,183,186],filter:[6,13,30,83,89,99,168,184,185,188],filter_dur:82,filter_info_top:[93,106,109,112,181,183],filter_mask:93,filter_mask_data:183,filter_mask_serv:[181,183],filter_space_valu:93,final_bt_statu:161,find:[14,28,56,85,94,97,104,129,130,143,144,146,147,148,150,151,153,154,159,161,165,171,172,174,176,177,178,179,180],find_if:159,find_packag:177,findchessboardcorn:175,finder:[151,169],findpackageshar:171,fine:[94,147,172,183],finish:[150,178],finit:[28,94,186],first:[20,28,74,75,94,113,142,143,146,148,152,153,154,159,163,164,166,168,169,170,171,172,173,174,176,177,179,180,181,182,183,184,186],first_map_onli:83,first_map_only_:83,firstli:23,fit:[94,172,185],fix:[97,111,146,150,153,164,166,168,169,170,171,175],flag:[9,143,168,171,175,177,178],flagship:14,fleet:28,flexibl:[14,85,94,156],flip:[106,151,153,165,171],flip_threshold:106,flood:19,flow:[1,19,20,22,24,25,75,76,146,157,186],fluidli:94,fly:[151,177,186],fn_tol:88,focal:175,focallength:169,focu:[12,19,27,171,185,186],focus:176,focuscamera:171,folder:[20,143,144,169,175],folk:[146,152,177],folllow:168,follow:[1,2,3,9,10,18,19,22,24,25,27,29,45,52,78,84,87,88,89,90,93,96,97,104,112,125,126,127,142,144,146,147,148,149,150,151,152,153,154,156,158,159,160,161,163,165,166,167,168,169,170,171,172,173,174,175,176,177,178,180,181,182,183,184,185,187,188],follow_path_error_cod:[45,71,85],follow_path_error_code_id:173,followpath:[18,19,20,21,22,23,24,25,27,28,34,43,46,86,89,91,94,97,98,150,153,157,159,161,165,179,187],followpathact:[43,46,53],followpathrecoveryfallback:[19,22,24,86],followwaypoint:[27,153],fonction:152,fondli:14,fool:172,footprint:[2,84,87,90,94,102,109,110,114,129,134,152,153,154,158,165,167,171,185],footprint_clearing_en:[90,110,114],footprint_pad:90,footprint_top:[87,99,100,102,156,174],footprintapproach:87,footprintcost:27,footprintcostatpos:27,forc:[83,94,154],forcefulli:143,forese:150,forget:180,forgot:146,fork:[28,91],forklift:23,form:[5,87,103,158,169,170],formal:[28,148,176],format:[10,87,88,94,126,143,151,168,169,171,181,183,186],former:[14,87],formerli:[89,153,163],formul:154,formula:183,fortun:168,forward:[0,9,19,28,56,88,93,97,98,115,120,130,135,138,139,143,147,154,157,170,172,187],forward_point_dist:[91,132,136],forward_prune_dist:[115,153],forward_sampling_dist:[98,187],found:[3,8,20,23,27,28,70,98,101,115,128,129,130,143,144,148,149,151,152,153,156,157,158,159,160,161,163,164,165,166,168,169,171,173,178,180,181,182,183,184],foundat:161,four:[19,28],foxi:[11,28,160],fraction:152,fragment:176,frame:[2,28,51,56,59,61,70,77,83,84,85,87,88,90,93,102,106,109,110,112,114,118,141,149,159,160,166,168,169,170,171,175,185],frame_id:[27,93,110,114,159,160,168,181,182,183],frame_nam:169,framework:[0,2,8,14,28,101,148,153,168,172,173],francisco:[148,163],free:[10,28,90,93,94,111,128,141,144,149,163,168,169,171,172,176,180,181],free_spac:176,free_thresh:[181,183],free_thresh_default:93,freeli:171,freespac:[22,24,25,172],frequenc:[19,20,84,89,90,94,96,104,129,130,168],frequent:[130,172],fresh:143,friction:2,friendli:[94,171],from:[2,5,6,7,8,9,11,12,17,19,20,21,22,23,24,25,27,28,43,46,49,51,53,56,60,83,84,85,87,88,89,90,93,94,97,98,99,103,104,105,110,112,114,128,129,130,132,135,136,140,141,142,143,144,145,146,147,148,149,150,151,152,154,156,157,158,159,160,161,163,164,165,166,168,169,170,171,172,173,174,175,176,179,180,181,182,183,184,185,186,187],from_imag:142,from_msg:152,from_numb:156,from_second:159,front:[87,132,136,159,171,172,185],front_cast:171,frustrat:152,fsm:28,full:[5,7,12,20,28,83,90,94,109,115,141,146,150,151,152,164,165,166,167,168,170,171,172,176,179,181,183,186,187],fulli:[28,83,129,130,146,147,151,152,165,172,174,184],fun:[0,16],fundament:[161,177],further:[11,20,23,94,100,129,130,143,146,152,170,177],furthest:94,fuse:[28,164,168],fusion:[15,28,168,170],futur:[1,4,8,11,22,28,83,87,106,109,112,150,152,179],gain:[8,94,97],galact:[83,85,156,158,160,169,184,186],game:28,gamma:94,gap:171,gather:[14,28],gaussian:[83,94,168,169],gazebo:[1,2,3,4,5,6,7,9,10,11,12,13,141,147,156,157,158,159,160,161,166,167,171,172,176,180,181,183,184],gazebo_model_path:147,gazebo_ro:[152,168],gazebo_ros_camera:169,gazebo_ros_pkg:168,gazebo_ros_ray_sensor:169,gazeborosimusensor:168,gdb:[143,177],gdb_test_nod:177,gdb_test_pkg:177,gdbtester:177,gear:151,gen:94,gener:[0,3,5,10,19,23,28,79,87,88,95,101,103,104,115,128,130,143,144,145,148,149,151,152,153,163,165,166,168,169,170,172,173,176,177,178,182],general_goal_check:151,generate_launch_descript:[168,169,171,181,183],generos:172,gentl:172,genuin:161,geograph:168,geometr:[171,172],geometri:[4,5,9,168,169,171],geometry_msg:[41,42,47,51,56,78,150,159,160,161,168,182],get:[1,4,10,19,20,27,28,68,85,89,94,99,103,110,114,129,133,142,143,145,148,150,151,152,153,156,157,158,159,160,161,163,164,167,168,170,171,173,174,175,176,178,179,180,181,183,184,185,187,188],get_clock:159,get_logg:[156,157,159,160],get_package_share_directori:[161,177,178,181,183],get_paramet:[158,159,160,161],get_shared_package_path:151,getandtrackrout:27,getblackboard:161,getcostidx:27,getcostmap:160,getcostmaptimestamp:27,getcostxi:27,getcurrentbtfilenam:161,getdefaultbtfilenam:161,getdefaultbtfilepath:161,getfeedback:[27,152],getglobalcostmap:27,getglobalframeid:[27,160],getindex:[27,158],getinput:157,getlocalcostmap:27,getnam:161,getorigini:27,getoriginx:27,getpath:27,getpaththroughpos:27,getresolut:27,getresourceinfo:153,getresult:[27,152],getrout:27,getsizeincellsi:27,getsizeincellsx:27,getsizeinmetersi:27,getsizeinmetersx:27,gettoler:151,ghcr:142,gif:23,gimp:181,gine:[97,148],git:[5,142,144,146,175,181,182,183,184],github:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,144,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],give:[11,94,146,147,148,150,156,157,164,165,168,169,170,171,172,173,177,183,187],given:[3,6,23,27,28,31,34,44,52,54,84,87,94,99,100,106,150,151,152,153,154,157,158,159,160,163,165,168,172,174,178,186],global:[19,22,23,24,25,27,50,60,62,66,79,83,84,86,88,97,113,118,136,137,149,150,152,153,154,158,159,160,163,166,168,169,170,171,172,176,180,181,183,184],global_costmap:[19,22,23,24,25,84,86,90,99,100,102,106,109,112,156,157,158,166,169,174,176,181,183,184],global_costmap_top:[84,156],global_footprint_top:[84,156],global_fram:[51,59,61,77,84,85,90,153,156,157,158,161,169],global_frame_:160,global_frame_id:83,global_path:160,global_plan_:159,global_plan_pos:159,global_plann:17,global_planner_plugin:160,globallyupdatedgo:86,globalplann:160,globalupdatedgo:[25,60],gmail:2,gnu:[177,184],goal:[11,18,19,20,21,22,24,25,27,28,34,41,42,45,47,48,51,55,60,61,62,67,78,79,85,86,88,89,95,96,97,115,121,122,123,124,128,129,130,132,133,139,140,147,149,150,156,157,159,160,161,168,171,172,173,174,179,182,183,185,187],goal_:157,goal_blackboard_id:[85,161],goal_blackboard_id_:161,goal_check:[46,89,91,97,98,151,159,187],goal_checker_id:[27,45,46],goal_checker_nam:115,goal_checker_plugin:[89,91,97,98,150,151,187],goal_checker_plugin_id:[122,124],goal_checker_selector:46,goal_distance_bia:115,goal_pos:[27,151,152,159,161,182],goal_reached_tol:61,goal_sub_:161,goal_upd:[78,179],goal_updater_top:78,goalalign:[91,115],goalaligncrit:91,goalanglecrit:94,goalcheck:[46,150,152,159],goalcheckerselector:[22,24,25,86,151],goalcomplet:161,goalcrit:94,goaldist:[91,115],goaldistcrit:91,goalreach:[20,77,80,82,86],goalreceiv:161,goals_blackboard_id:[85,161],goaltool:180,goalupd:[19,20,22,23,24,25,60,86,157],goalupdat:[21,86,179],goalupdatedcondit:150,goe:[9,20,23,112,152,156,159,160,161,174],going:[4,14,27,28,79,94,148,151,152,157,174,177,179,181,183],golai:[29,163],gone:19,good:[1,6,28,83,94,103,104,129,146,148,154,156,158,159,160,161,166,167,171,172,175,177],googl:146,gothroughpos:27,gotopos:[27,152],gpal:88,gpu:[4,143],grab:[88,144,161,168],grade:[28,148,168],gradient:[5,28,88,99,152,158],gradient_factor:158,gradient_index:158,gradient_lay:158,gradient_layer_1:158,gradient_layer_2:158,gradient_plugin:158,gradient_s:158,gradient_tol:88,gradual:88,grai:[171,183],grant:143,granular:[88,120],graph:[3,10,103,130,153,164,178],graphic:[8,144,181,183],grasp:169,great:[7,14,19,146,152,177],greater:[3,94,103,143,159,173],green:[88,164,175,180,186],grei:183,grep:141,grid:[6,7,28,90,93,110,114,118,163,165,166,169,171,182,184],grid_map:5,gridbas:[19,21,22,23,24,25,41,42,49,86,95,96,103,128,129,130,151,157,160,165,174,179],groot:[85,86,188],ground:[166,168,171],group:[11,13,14,28,80,107,146,153,163,176],group_connectivity_typ:[107,176],gtest:12,guarante:[98,104,129,148,165,170,187],gui:[2,144,147,168,171,175,186],guid:[18,19,20,142,144,150,152,153,154,158,160,164,165,166,168,169,170,171,173,184,185],guidelin:153,guillaum:163,gzclient:147,habit:172,hackbaselin:169,had:[12,14,152,153,169],haghighipanah:163,half:[19,97,129,130,169],hall:172,hallmark:6,halt:[19,20,23],hand:[28,94,98,104,152,154,166,170,171,172,187],handi:143,handl:[11,17,19,23,27,28,84,87,89,92,93,96,102,143,151,152,153,156,157,158,159,160,161,169,171,172,173,177],handler:154,hangout:146,hansen:14,happen:[14,19,146,159],happi:146,hard:[10,14,22,52,87,149,151,161,172],hardcod:[22,24,25,153,157,161],hardwar:[87,104,143,165,169,171,184,186],harsh:152,harshli:103,has:[2,3,4,6,8,11,12,14,17,19,20,22,23,24,25,27,51,59,60,62,68,69,84,86,88,94,97,111,121,122,123,124,128,129,130,141,143,144,146,147,148,150,151,152,153,154,156,157,158,159,161,163,166,168,169,170,171,172,177,178,180,181,183,185,186,187],has_paramet:161,have:[0,3,4,6,10,11,12,14,16,17,19,20,22,23,24,25,27,28,51,84,87,89,90,94,95,96,97,101,102,103,105,106,109,112,128,129,130,141,143,144,146,148,150,151,152,153,154,156,157,158,159,160,161,163,165,166,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],head:[35,44,94,97,98,128,130,146,152,163,167,168,170,172,179,187],header:[149,158,159,160,168,182],headless:[144,147,172,176,185],headlight:[106,153],hear:172,heart:[28,165],heavi:[87,88,129],heavili:172,height:[27,87,90,97,110,114,158,169,171],hello:156,help:[2,3,4,5,8,11,16,22,24,25,28,88,97,130,145,146,149,151,152,153,156,158,160,163,165,167,168,170,171,172,173,178,181,184,186,187],henc:[152,166,169,171,173],here:[0,3,14,20,22,23,24,28,74,75,76,77,78,79,80,81,82,87,94,98,143,144,146,147,149,150,151,152,153,154,157,158,159,160,161,163,168,171,173,174,175,177,180,182,186],heurist:[28,97,101,128,129,130,151,152,165],hfsm:28,hide:171,hierarch:[28,186],high:[2,3,4,5,6,8,28,87,94,97,100,103,104,114,128,129,130,146,148,149,151,165,168,176],higher:[4,6,9,12,19,28,87,88,90,94,104,106,129,130,148,151,152,153,161,172,173,179,181,183,186],highest:[28,153],highli:[17,28,88,94,101,138,147,148,154,163,165,170,172,174,180,182,184,187],highlight:[8,18,27,88,143,165,175,186],hint:172,histori:171,hit:[177,183],hold:[28,169,186],holder:[146,151],holonom:[88,89,94,97,140,148,163,172],home:[126,152,172,177,179],hood:[11,152],hooper:163,hope:152,hopefulli:[19,94],horizon:154,horizont:[107,169],horizontal_fov:169,horizontal_fov_angl:184,hospit:1,host:[17,28,84,89,93,96,102,105,143,144,149,156,165,178],hot:161,hotel:[181,183],hour:180,hous:106,how:[2,7,18,27,28,75,83,86,87,88,94,103,110,114,118,132,133,136,137,143,145,146,149,153,156,157,158,159,160,161,165,166,167,168,169,170,171,172,173,174,175,177,178,179,180,181,182,183,184,185,186,187],how_many_corn:103,howev:[4,6,9,14,21,22,24,25,28,87,94,99,143,147,150,151,152,156,161,166,168,171,172,174,177,181,183,184,185,187],hpp:[156,158,159,160,161],html:142,http:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],huerist:151,huge:94,human:[1,4,28,163],humbl:[83,84,87,89,91,94,97,98,147,156,185,186,187],hundr:[1,28],hurt:169,hybrid:[3,98,101,130,143,151,152,153,154,163,165,166,172,187],hypot:[159,160],hypothet:19,icon:186,idea:[17,147,148,152,171,172],ideal:[7,12,152,153,156,159,160],identifi:[4,7,11,13,143,151,158,165,178],idl:20,ieee:148,ifcondit:[168,171],ifunspecifi:168,ignit:164,ignor:[83,141,142,157,168,176],illustr:176,ilqr:3,imag:[16,23,28,88,99,126,130,149,151,171,174,175,176,181,183],image_format:126,image_pipelin:175,image_raw:[126,169,175],imagin:[19,28,156,163],immedi:[22,24,87,92,151,156,161,168,171,177],immin:[87,148],impact:[22,24,94,172,177],impass:181,impl:126,implement:[3,5,6,7,10,17,21,22,24,25,28,30,31,41,42,44,45,47,48,54,57,75,83,84,85,89,90,92,93,94,95,96,97,101,102,103,104,105,144,146,149,151,152,153,156,159,160,161,163,165,166,168,169,172,173,174,182,184,186],implementaion:163,impli:126,implicit:27,implicitli:152,improv:[1,7,9,11,12,26,28,88,99,101,129,130,143,147,149,150,151,153,154,164,178],imu0:168,imu0_config:168,imu:[28,168,169,170],imu_joint:168,imu_link:168,imu_plugin:168,imu_sensor:168,inact:[28,94,156,159,160,161,171,173],incentiv:[94,154],includ:[4,6,7,10,13,14,19,27,28,75,85,86,101,106,120,142,143,144,145,146,148,149,150,151,156,157,158,159,160,161,163,165,168,169,170,171,177,178,179,181,182,183,184,187],include_last_point:120,inclus:[143,154,169,177],incom:[87,106,109,112,150,181,183],incompat:143,incomplet:164,inconsist:151,incorpor:[83,143,151],incorrect:[151,163],incorrectli:151,increas:[12,28,88,94,103,152,153,170,172,173,175],increasingli:28,incred:18,increment:[30,84,87,129,152],increment_recovery_count:157,indefinit:[19,20,27,146,179],independ:[14,28,84,112,148,151,153,157,169,185],index:[27,126,142,156,158,159,160,161,163,186],indic:[52,83,87,106,109,112,125,146,150,151,157,158,169,183],individu:[11,17,28,101,146,149,152,153,172,182],indoor:106,induc:[153,163,188],industri:[14,28,87,97,151,163,165,181],inerti:[169,171],inertia:[168,169,171],inf_is_valid:[90,110,114,184],infeas:[100,163],infer:171,infin:56,infinit:[21,89,110,114,129,130],inflat:[28,83,90,109,111,131,163,169,176,181,184],inflate_around_unknown:[90,108],inflate_con:111,inflate_unknown:[90,108],inflation_lay:[90,106,107,109,112,158,166,169,176,181,183],inflation_radiu:[90,94,108,169],inflationlay:[90,169],influenc:94,info:[10,88,91,106,109,112,144,151,158,168,175],inform:[1,2,4,10,20,21,28,87,93,94,97,98,101,104,106,109,110,112,114,115,128,129,130,142,146,149,150,152,153,154,156,157,158,159,160,161,163,168,169,170,171,172,173,174,176,177,178,180,181,182,183,184,185,186],infrar:169,infux:152,ing:20,inher:[143,144],inherit:[151,157,158,159,160,161],init:[27,152],init_pos:27,initalorientationasrefer:168,initi:[8,27,63,70,83,94,100,141,143,144,147,150,152,153,156,158,159,160,161,163,171,172,179,181,185],initial_cov_:83,initial_orientation_as_refer:168,initial_pos:[27,63,83,152],initial_pose_:83,initializegoalpos:161,initialposereceiv:[20,86],inject:177,injuri:9,inlin:[158,160,184],inner:[11,185],inorm:158,inout_port:186,inproceed:148,input:[6,20,27,28,85,87,88,94,99,100,110,111,114,125,148,151,153,156,157,158,159,160,163,168,171,174,177,179,185,186],input_at_waypoint:125,input_go:[21,22,51,78,179],input_path:[21,55,56,179],input_port:186,input_sensor_typ:[111,169],input_top:125,inputatwaypoint:[105,151,163],inputport:157,inquiri:14,inscrib:[152,172],inscribed_inflated_obstacl:176,insert:[157,169,177],insid:[28,87,88,89,91,101,105,143,144,152,153,158,168,169,173,177,178,181,184,185],insight:[11,152,164,172],inspect:[27,143],instabl:152,instal:[141,143,144,145,156,158,159,160,161,166,168,169,170,171,174,175,176,177,178,180,181,182,183,185,187],instanc:[28,87,126,147,154,157,165,168,173,181,183],instantan:[89,153],instanti:[165,171,173],instead:[13,19,22,24,25,78,83,94,100,115,142,143,149,150,151,152,153,154,156,161,168,169,170,172,173,174,177,179,180,181,185],instruct:[28,105,147,156,158,159,160,161,168,169,177,178,182],instrument:94,int16:173,integ:181,integr:[0,1,7,12,17,18,29,56,87,97,144,151,152,167,168,169,170,173,177,186],intel:[4,14,94,152],intel_realsense_r200_depth:[87,90,184],intellig:[148,172],intellisens:143,intend:[85,147,150],intent:[23,94,172],intention:[14,88,181],interact:[28,85,86,94,148,151,152,171,173,174,177,188],intercorrel:176,interest:[7,10,11,14,18,27,28,143,146,161,170,172,174,177,178,179,180,182,186],interfac:[3,5,13,17,20,28,85,87,102,143,144,148,149,150,153,156,157,158,161,163,169,174,180,184],interfer:[90,181],interior:175,intermediari:[22,148,151],intern:[19,22,24,25,98,148,153,158,161,168,173,187],interoper:169,interpol:[97,104,181],interpolation_resolut:160,interpolation_resolution_:160,interpret:[90,93,170,176],interprocess:143,intersect:97,interti:171,interv:87,interven:1,intial_pos:20,intrest:177,introduc:[28,97,144,146,149,151,152,167,169,171,173,176],introduct:[18,86,171],intuit:[172,187],inturn:23,invalid:[18,27,143,153,161],invers:[94,154,181],inversion_xy_toler:94,inversion_yaw_toler:94,invert:[25,94,151],investig:177,invilad_start:173,invok:[30,31,41,42,44,45,47,48,52,54,57,142,143,173,178],involv:[4,5,6,11,19,21,94,97,145,151,153,154,166,173],ipc:143,iro:148,iron:[85,93,161],irregular:149,is_recoveri:[26,30,54],is_voltag:65,isbatterycharg:[86,153],isbatterylow:[19,20,86],isbatterylowcondit:150,ish:14,isn:[94,146,177],isol:[144,178],ispathvalid:[25,86],isstuck:86,issu:[0,2,3,5,6,8,14,22,24,25,27,28,94,146,150,151,152,164,165,170,172,176,177,181,183,184],istaskcomplet:[27,152],item:[2,11,19,27,28,164],iter:[22,24,25,27,28,51,85,87,88,91,94,100,104,128,129,130,153,158],iteration_count:94,its:[1,6,8,9,11,12,19,20,22,23,24,25,27,28,77,80,81,82,87,88,90,94,95,98,100,101,103,128,129,130,142,146,149,150,151,152,153,156,158,159,160,161,163,165,166,168,169,170,171,172,173,174,175,176,177,178,181,183,184,185,186,187],itself:[28,112,129,130,143,152,157,161,169,174,181,183,186],ixi:[169,171],ixx:[169,171],ixz:[169,171],iyi:[169,171],iyz:[169,171],izz:[169,171],jag:100,jaggedli:94,jerk:183,jerki:[94,104],jeronimo:163,jetbrain:144,jetson:4,jitter:94,job:[28,94],join:[146,166,168,169,171,181,183],joint:[168,169,171],joint_state_publish:[168,171],joint_state_publisher_gui:[168,171],joint_state_publisher_gui_nod:[168,171],joint_state_publisher_nod:[168,171],jonatan:148,joshua:[14,163],joshuawallac:14,journal:148,jpeg:151,jpg:151,json:[2,143,144],jump:168,june:101,junior:146,just:[8,21,22,24,25,28,79,90,94,135,144,146,152,157,158,166,168,169,170,171,177,178,181],juzhenatpku:2,kalman:168,kcachegrind:178,keep:[14,19,28,87,94,143,150,151,154,157,159,160,163,168,170,171,181,186],keep_goal_orient:88,keep_start_orient:88,keepout:[90,93,151,163,183,188],keepout_filt:[90,109,176,181],keepout_filter_mask:181,keepout_mask:181,keepout_param:181,keepoutfilt:[90,109,151,181],keeprunninguntilfailur:[21,179],kei:[20,83,143,146,147,161,173,176],kept:[14,107],kernel:176,key_nam:186,key_name2:186,kick:[28,156],kidnap:50,kill:177,kind:[23,168,177],kinemat:[2,91,98,100,101,148,151,163,165,168,171,172,187],kinodynam:3,know:[11,14,28,97,101,141,146,150,151,157,158,163,170,171,183,186],knowledg:[4,7,11,146,177,184],known:[19,23,27,28,83,97,152,161,163,172,175,184],konolig:163,kurt:163,label:143,laid:[181,183],lambda:157,lambda_short:83,land:8,landmark:168,lane:[28,93,109,151,163,181],languag:174,larg:[20,28,87,94,97,129,130,150,164,168,171,172,175],larger:[28,79,92,94,97,99,128,146,151,163,177,185],largest:[165,166],laser:[6,9,83,87,110,114,163,169,170,185],laser_likelihood_max_dist:83,laser_link:171,laser_max_rang:83,laser_min_rang:83,laser_model_typ:83,laserscan:[87,90,110,114,153,182],last:[6,14,20,22,24,55,56,83,88,95,101,103,104,120,128,129,130,132,133,136,137,143,152,161,165,166,168,170,171,173,181,183],lastli:[146,153,165,166,168,169,170,171],latenc:[17,104,149,150],later:[5,94,129,130,143,144,146,152,156,157,158,159,160,161,169,178,184,186],latest:[87,142,143,187],latter:174,lattic:[3,98,101,129,152,153,163,164,165,172,187],lattice_filepath:130,launch:[17,28,84,92,93,144,147,156,158,159,160,161,165,166,170,173,175,176,179,181,183,185,186],launch_ro:[168,171,177,181,183],launchconfigur:[168,171,181,183],launchdescript:[168,171,181,183],layer:[2,4,7,10,11,90,106,109,111,112,128,129,131,143,148,149,151,152,158,169,172,181,184],layeredcostmap:158,lazi:151,ld_preload:184,lead:[14,94,97,126,146,151,152,183],leader:14,leadership:14,lean:142,learn:[4,7,11,19,28,86,144,148,156,157,160,169,170,171],least:[21,87,143,146,151,168,185],leav:[94,97,150,177,185],led:153,left:[6,28,41,42,97,103,113,129,130,143,147,152,159,160,166,168,169,171,175,176,178,180,183,186],left_joint:168,left_wheel_est_vel:168,leg:[101,144,148,163,165,172],legaci:115,length:[79,88,90,94,103,129,130,152,169,171,172,173,175],length_factor:[23,79],less:[9,61,87,94,96,97,107,149,152,168,176,181,187],let:[11,19,20,28,125,127,141,144,151,152,156,157,160,168,169,170,171,172,179,183,185],lethal:[90,94,108,163,169],lethal_cost_threshold:90,lethal_obstacl:[158,176],level:[5,9,17,19,22,24,25,28,87,100,146,148,151,152,153,173,178,181,183,186],leverag:[7,11,27,142,144,152,172,174,179],lib:[177,184],libgazebo_ros_camera:169,libgazebo_ros_diff_dr:168,libgazebo_ros_factori:[152,168,169],libgazebo_ros_imu_sensor:168,libgazebo_ros_init:[152,168,169],libgazebo_ros_ray_sensor:169,libjemalloc:184,libjmalloc:184,librari:[5,6,7,10,15,17,27,28,85,149,150,152,156,158,159,160,161,169,170,174,177,184,186],libstdc:177,licens:[1,2,3,4,5,6,7,8,9,10,11,12,13,145],lidar:[6,9,28,166,168,169,176,184],lidar_joint:169,lidar_link:[169,170],life:186,lifecycl:[17,27,29,104,141,148,150,151,161,165,167,172,178,181,183],lifecycle_manag:[92,173,181,183],lifecycle_manager_costmap_filt:[181,183],lifecycle_manager_navig:173,lifecycle_nod:[173,181,183],lifecyclemanag:152,lifecyclemanagercli:152,lifecyclenod:[28,152,159,161,177],lifecycleshutdown:27,lifecyclestartup:27,lifecyl:173,light:[106,152,175,181,183],lightli:94,like:[2,4,8,13,14,18,19,20,21,22,24,25,27,28,85,93,94,101,105,128,143,144,146,147,148,151,152,156,157,158,161,163,166,167,169,170,171,172,173,174,177,178,179,181,182,183,184,186,187],likelihood:83,likelihood_field:83,likelihood_field_prob:83,limit:[8,28,87,89,93,94,104,112,128,129,130,143,151,159,163,165,168,172,179,188],limitedaccelgener:91,line:[12,27,99,128,150,153,156,158,159,160,161,165,166,168,169,170,171,172,174,177,178,185],linear:[31,44,87,88,93,97,120,151,153,159,168,181],linear_acceler:168,linear_granular:[91,120],linear_limit:[87,153],linear_solver_typ:88,linear_vel:159,linearli:[28,112,151,181,183],linecost:27,link:[1,2,3,4,5,6,7,8,9,10,11,12,13,16,20,103,146,152,168,169,170,171],links1:171,lint:146,linter:143,linux:[143,144,177,184],list:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,20,22,27,47,48,51,84,85,87,89,90,91,92,96,101,102,105,115,143,144,146,148,149,150,151,153,157,158,159,161,163,164,165,168,169,172,173,175,176,177,181,183,186,187],listen:[20,84,87,141,150],lit:175,littl:[172,177],live:[4,28,144,151,156,170,172,180,182,186],lld:142,load:[28,45,84,89,90,93,94,96,102,105,115,143,148,149,150,151,152,156,157,158,159,160,161,163,165,169,171,174,178,181,183,184,186],loadabl:[90,150,151,184],loadbehaviortre:161,loadlibrari:184,loadmap:83,local:[1,3,9,10,11,19,22,24,25,27,43,46,49,53,83,84,92,94,97,104,115,118,122,143,144,146,147,148,150,151,152,153,158,159,160,161,163,165,166,170,172,176,181,183,184,185],local_costmap:[19,22,23,24,25,38,39,40,84,86,87,90,107,109,156,157,158,166,169,176,181,183],local_costmap_top:[84,156],local_footprint_top:[84,156],local_fram:[84,153],local_or_glob:151,local_plann:17,localization_lifecycle_manag:150,locat:[9,23,27,28,129,130,139,147,156,158,159,160,161,165,168,169,171],lock:[13,159,161],lockfil:143,locu:14,log:[144,146,152,156,157,168,169,177],logger:152,logger_:[159,161],logic:[9,18,19,22,24,25,28,153,157,161,173,186],logininteractiveshel:143,logo:8,longer:[8,17,23,79,128,152,153,156,177],look:[0,2,11,19,51,84,97,132,136,139,146,147,148,150,157,165,168,169,170,171,172,173,178,181,183,184,185,186,187],lookahead:[97,151,159,187],lookahead_dist:[97,159],lookahead_dist_:159,lookahead_tim:[91,97,139],looker:[172,187],lookup:[56,152],lookup_table_s:[129,130],loop:[20,28,94,97,104,152,160,161],loop_rat:[105,151],loss:87,lot:[168,171,177],loung:148,low:[5,17,19,20,65,94,99,104,149,163],lower:[14,19,65,84,87,94,106,152,153,169,173],lowest:[47,48,94,151,153,173],luckili:[170,177,186],luggag:179,macenski2020marathon2:148,macenski2023regul:148,macenski2023survei:148,macenski:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,97,148,163],machin:[4,17,28,143,144,168,169,170,173,186],macro:[129,130,156,157,158,159,160,161,171],made:[6,8,28,87,89,90,92,121,123,143,144,146,152,153,158,161,165,166,171,172,176,179,181,183,185],mai:[0,3,4,5,6,10,14,22,24,25,27,28,79,87,94,97,99,101,109,129,130,135,142,143,146,148,150,151,152,153,154,157,158,161,164,165,166,168,169,170,171,172,173,174,176,177,178,179,180,181,183,186,187],main:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],main_tree_to_execut:[18,19,20,21,22,23,24,25,26,86,157,179],mainli:[19,169,170,171],mainstai:[28,101],maintain:[0,8,14,15,17,143,146,148,152,153,161,163,164,169,172,173],maintre:[18,19,20,21,22,23,24,25,26,86,157,179],major:[10,13,28,101,148,151,156,161,164,166,171,177],make:[1,2,7,9,10,11,12,13,14,17,20,22,24,25,26,28,55,56,89,94,97,98,103,110,112,114,140,141,143,144,146,150,151,152,153,154,156,159,160,161,163,165,166,168,169,170,171,172,173,175,176,177,178,179,180,181,182,183,184,185,187],make_shar:161,make_uniqu:157,malici:144,manag:[27,28,29,143,147,148,150,151,165,167,168,170,171,172,173,175,178],mandatori:[151,156,157,159,160,183],maneuv:[94,129,130,150,166],mani:[11,17,18,19,22,24,25,28,75,83,87,148,149,150,158,163,169,170,172,174,177,178,179,181,183,186,187],manipul:[10,27,171],manner:[28,148],manual:[0,56,92,142,143,147,168,173,178],manufactur:169,map:[27,28,29,41,42,45,51,59,61,77,83,84,85,89,90,96,106,109,110,112,113,114,128,129,130,141,147,148,149,151,154,157,158,159,160,161,163,165,166,168,170,172,176,180,181,183,185,186,188],map_filepath:27,map_fram:168,map_io:150,map_load:150,map_sav:[93,150],map_save_dur:184,map_saver_cli:[150,182],map_serv:[17,83,90,93,150,181,183],map_subscribe_transient_loc:[90,113,169],map_top:[83,90,113,169],mapped_name_of_plugin:[159,160],mapper_params_online_sync:177,mapping_mod:184,mapsav:152,mapserv:150,maptoworld:27,marathon:148,march:28,marder:163,margin:[94,130],mark:[4,28,88,90,110,111,114,134,153,161,169,176,181,183,184,186],mark_threshold:[90,111,114,169,184],marker:[94,118,146,169,171],marker_lifetim:118,market:11,martin:[97,148],mask:[28,93,106,109,112,151,153,163,176],mask_top:[93,181,183],mask_valu:[93,106,112],mask_yaml_fil:[181,183],mass:[169,171,183],massiv:[156,169,176],master:[110,114,158,164,169],master_arrai:158,master_grid:[110,114,158],match:[6,58,71,72,73,83,84,85,94,102,129,130,148,153,157,159,166,172,173,185],matchsiz:158,matej:163,materi:171,matrix:[28,168],matt:14,matur:[24,25],max:[88,94,97,110,111,114,128,129,130,154,159,169],max_accel:104,max_allowed_time_to_collis:97,max_allowed_time_to_collision_up_to_carrot:97,max_angl:169,max_angle_to_furthest:94,max_angular_accel:[97,98,187],max_angular_vel:159,max_angular_vel_:159,max_beam:83,max_decel:104,max_dur:27,max_height:87,max_i:158,max_it:100,max_iter:[88,128,129,130],max_j:158,max_linear_accel:152,max_linear_decel:152,max_lookahead_dist:97,max_obstacle_height:[90,110,114,169,184],max_on_approach_iter:[128,129,130],max_particl:83,max_path_occupancy_ratio:94,max_planning_tim:[128,129,130,151],max_planning_time_m:151,max_point:[87,153,185],max_rat:82,max_robot_pose_search_dist:[56,94,97],max_rotational_vel:[84,156],max_scaling_factor:115,max_smoothing_dur:52,max_spe:[82,94],max_speed_xi:[91,117],max_vel_i:[91,117],max_vel_theta:[91,117],max_vel_x:[91,117,150],max_veloc:104,max_wheel_acceler:168,max_wheel_torqu:168,max_z:184,maxim:[88,94,172],maximum:[2,28,52,56,82,83,84,87,88,89,90,93,94,97,98,100,104,110,112,114,117,121,123,128,129,130,151,152,153,159,163,169,176,181,183],maxwithoutunknownoverwrit:[110,114,154],mayb:2,mcl:6,mean:[0,1,19,20,28,87,94,104,112,129,143,144,150,153,168,169,170,172,176,181,183],meaning:[152,161,173],meant:[87,103,152,153,167,172],meantim:13,measur:[9,26,89,94,110,114,129,130,151,153,163,168,169,170,171,176],mechan:[5,11,87,158,177],medium:[1,7,8,9,11,12,13,164],meet:[94,122,139,146],member:[4,146,156,159,160,161],memori:[28,143,152,172,173,177,184],mention:[149,150,151,165,183,187],mentor:[0,1,2,3,4,5,6,7,8,9,10,11,12,13],menu:186,mere:143,merg:[5,13,143,146,150,158],merit:144,merzlyakov:[14,148,163],mesh:[28,171],messag:[11,27,28,30,31,41,42,43,44,46,49,53,54,83,84,87,89,90,96,110,112,114,143,146,151,153,156,157,159,161,168,173,181,183,185],message_success:156,messsag:146,met:[124,139,146,151,187],meta:[181,183],metadata:[28,143,161,181,183,186],metapackag:[5,17],meter:[18,26,27,28,83,90,95,98,128,129,130,175,176,187],method:[3,4,6,18,22,24,25,27,28,92,94,110,114,132,133,136,137,146,151,152,153,156,157,158,159,160,161,177,178,186],metric:[101,153,157],michael:163,micro:172,mid:28,middl:[99,165,172,183,186],middlewar:28,might:[28,83,94,104,151,161,166,168,169,177,178,181,183,186],migrat:[8,164],miguel:163,mike:14,millisecond:[85,127,151],mimic:171,min:[111,159,164,169],min_angl:169,min_approach_linear_veloc:97,min_batteri:65,min_dist_to_obstacl:94,min_height:87,min_i:158,min_j:158,min_lookahead_dist:97,min_obstacle_height:[90,110,114,169,184],min_particl:83,min_point:[87,153,185],min_rat:82,min_rotational_vel:[84,156],min_spe:82,min_speed_theta:[91,117],min_speed_xi:[91,117],min_theta_velocity_threshold:[89,91,97,98,187],min_turning_r:94,min_vel_i:[91,117],min_vel_x:[91,117],min_veloc:104,min_x_velocity_threshold:[89,91,97,98,187],min_y_velocity_threshold:[89,91,97,98,187],min_z:184,mind:[94,143,168,170],minim:[2,11,94,147,152,153,161,165,168,172],minima:94,minimal_group_s:[107,176],minimum:[2,9,28,65,82,83,84,87,88,90,93,94,97,104,107,110,114,117,121,123,129,130,135,138,151,152,153,163,165,169,170],minimum_turning_radiu:[88,129],minor:[122,169],minut:[28,175],mirror:[94,130],misalign:176,misloc:176,miss:[13,151,171,172,178,186],mission:156,mittal:163,mixin:[142,143],mixtur:83,mkdir:[142,181,183],mkhansen:14,mmethod:157,mnimum:121,mobil:[1,4,5,7,9,10,12,14,27,28,148,168,169,170],modal:168,mode:[21,87,94,104,143,153,154,181,183,186],model:[4,17,28,29,83,87,88,101,129,143,147,148,150,151,163,165,168,169,171,172,180,184,185],model_dt:94,model_typ:184,modelplugin:168,moder:172,modern:[101,148,172],modest:94,modif:[28,143,146,151,152],modifi:[6,18,55,56,85,86,91,99,143,146,151,152,154,156,157,159,160,161,163,165,166,168,171,177,178,179,186],modu:187,modul:[30,31,41,42,44,45,47,48,54,57,85,92,105,158],modular:[6,144,148,163],mohammad:163,moment:153,monitor:[23,29,148,151,186,188],monitorandfollowpath:23,monocular:175,monolith:17,mont:[6,28,83,169],month:146,moor:[15,148],more:[2,3,4,6,7,9,10,11,12,14,17,18,19,24,25,28,56,83,87,88,91,94,97,98,104,106,109,112,128,129,130,138,142,143,144,146,148,150,151,152,154,156,157,158,159,160,161,163,165,166,167,168,169,170,171,172,173,175,176,177,178,179,180,181,182,183,184,185,186,187],moreov:176,most:[9,19,22,24,25,83,87,94,98,101,147,152,157,163,168,169,170,172,174,177,178,187],mostli:169,mothership:156,motion:[3,4,28,83,88,129,130,138,139,151,154,163,165,168,170,186],motion_model:94,motion_model_for_search:129,motiv:[10,152],motor:[104,148],mount:[143,144,170],move:[14,19,23,28,79,87,94,106,121,123,125,130,135,138,148,149,150,151,152,153,160,163,164,170,171,172,175,179,180,181,182],move_bas:17,movecamera:171,moveit:[8,14],movement:[83,87,88,104,130,153,185],movement_time_allow:[89,91,97,98,121,123,153,187],mpc:[3,94,153,163,165],mppi:[153,163,164,172],mppicontrol:94,msg:[27,41,42,47,51,79,87,106,152,159,160,161,163,168],much:[28,88,97,104,146,148,150,151,153,170,171,172,181],multi:[7,10,11,28,151,152,163,165],multi_tb3_simulation_launch:154,multipl:[6,11,17,22,24,25,28,43,46,49,53,79,84,87,101,102,144,148,150,151,154,159,160,165,168,169,170,171,172,173,174,177,183],multipli:[93,106,112,128,129,181,183],multithread:0,multitud:[28,169],must:[4,14,20,27,28,59,83,90,93,97,100,104,107,110,114,121,123,129,130,131,146,150,152,153,156,157,159,160,161,163,165,168,169,170,173,174,175,178,180,182,184,186],my_camera:175,my_contain:173,my_mark:169,my_nav_through_poses_bt:[85,161],my_nav_to_pose_bt:[85,154,161],my_packag:[85,154,161],my_world:169,myawesomenewnod:186,myplugin:[158,160,184],naiv:[101,128],name:[8,14,15,18,19,20,21,22,23,24,25,26,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,53,54,57,83,84,85,86,87,89,90,92,95,96,102,103,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,142,143,146,150,151,152,158,163,164,165,166,168,169,170,171,172,173,174,175,177,178,179,181,183,184,185,186,187],name_:[158,160],name_of_paramet:[159,160],namespac:[28,84,85,89,90,91,94,96,102,105,110,114,115,150,153,154,158,159,160,165,168,169,172,173,181,183,184,187],narrow:[94,143],narrowest:94,nasti:[101,152],nativ:[143,153],natur:[28,94,154,161,172],nav2:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,19,21,22,23,24,25,26,27,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,142,143,144,145,146,147,149,150,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,170,171,174,175,182,184,186,187,188],nav2_amcl:[17,83,169,182],nav2_back_up_action_bt_nod:[85,157],nav2_behavior:[30,31,44,54,57,84,152,156],nav2_behavior_tre:[20,28,86,150,151,157,161,186],nav2_bringup:[147,150,151,152,153,156,158,159,160,161,166,169,172,176,177,178,179,180,181,182,183,185],nav2_bt_navig:[17,18,19,85,150,151,161,179,186],nav2_bt_waypoint_follow:28,nav2_ceres_costaware_smooth:[102,174],nav2_clear_costmap_service_bt_nod:85,nav2_collision_monitor:185,nav2_common:[181,183],nav2_compute_path_to_pose_action_bt_nod:85,nav2_constrained_smooth:[88,152],nav2_control:[17,89,91,97,98,121,122,123,124,149,151,153,178,185,187],nav2_cor:[17,85,149,151,153,156,159,160,161],nav2_costmap_2d:[17,90,106,107,109,112,150,151,152,153,158,159,166,176,181,183],nav2_costmap_2d_mark:169,nav2_costmap_filters_demo:[181,183],nav2_default_view:180,nav2_depend_w:141,nav2_distance_controller_bt_nod:85,nav2_distance_traveled_condition_bt_nod:85,nav2_dwb_control:17,nav2_follow_path_action_bt_nod:85,nav2_gazebo_spawn:152,nav2_goal_reached_condition_bt_nod:85,nav2_goal_updated_condition_bt_nod:85,nav2_gradient_costmap_plugin:158,nav2_gradient_costmap_plugin_cor:158,nav2_hfsm_navig:28,nav2_initial_pose_received_condition_bt_nod:85,nav2_is_stuck_condition_bt_nod:85,nav2_lifecycle_manag:[17,173,181,183],nav2_map_serv:[17,181,182,183],nav2_mppi_control:94,nav2_msg:[27,28,89,150,151,157,181,183],nav2_multirobot_param_al:154,nav2_multirobot_params_:154,nav2_navfn_plann:[17,95,96,160,165],nav2_param:[151,152,153,156,158,159,160,161,166,172,173,174,176,178,181,183,184],nav2_pipeline_sequence_bt_nod:85,nav2_plann:[17,41,42,149],nav2_pure_pursuit_control:159,nav2_rate_controller_bt_nod:85,nav2_recoveri:[149,152],nav2_recovery_node_bt_nod:85,nav2_regulated_pure_pursuit_control:[97,98,151],nav2_reinitialize_global_localization_service_bt_nod:85,nav2_rotation_shim_control:[98,152,187],nav2_round_robin_node_bt_nod:85,nav2_route_serv:173,nav2_rviz_plugin:17,nav2_sensor_driv:173,nav2_simple_command:[27,152],nav2_simple_navig:17,nav2_simulation_launch:147,nav2_single_trigger_bt_nod:85,nav2_smac_plann:[88,101,128,129,130,151],nav2_smooth:[88,99,100,102,174],nav2_sms_bahavior:156,nav2_sms_behavior:156,nav2_sms_behavior_plugin:156,nav2_speed_controller_bt_nod:85,nav2_spin_action_bt_nod:85,nav2_straightline_plann:160,nav2_straightline_planner_plugin:160,nav2_system_test:17,nav2_test_util:179,nav2_theta_star_plann:[103,151],nav2_time_expired_condition_bt_nod:85,nav2_transform_available_condition_bt_nod:85,nav2_tree_nod:186,nav2_util:[28,150,152,160,161],nav2_velocity_smooth:[104,152],nav2_w:[142,143,177],nav2_wait_action_bt_nod:[85,157],nav2_waypoint_follow:[17,28,105,125,126,127,149,151,153],nav2_world_model:149,nav:[14,27,151,152],nav_cor:17,nav_msg:[27,41,42,55,56,79,159,160,161,168,173],navfn:[3,17,29,94,98,99,101,149,163,165,166,172,174,187],navfnplann:[95,96,160,165],navig:[0,1,2,3,5,6,10,13,14,15,16,18,21,27,29,59,60,61,62,77,80,82,86,94,101,105,143,146,148,149,151,156,157,159,162,164,166,167,168,169,170,171,172,173,174,178,179,184,186,187,188],navigate_through_pos:[85,161],navigate_through_poses_error_cod:[47,85],navigate_through_poses_w_replanning_and_recoveri:[47,48],navigate_to_pos:[85,161],navigate_to_pose_error_cod:[48,85],navigate_to_pose_w_replanning_and_recoveri:[19,161],navigate_to_pose_w_replanning_goal_patience_and_recoveri:152,navigate_w_replanning_and_recoveri:[151,157,186],navigate_w_replanning_and_round_robin_recoveri:151,navigaterecoveri:[19,22,23,24,25,86,157],navigatethroughpos:[85,86,161],navigatethroughposesnavig:[85,161,163],navigatetopos:[28,85,86,105,150,157,161,179],navigatetoposeact:28,navigatetoposenavig:[85,161,163],navigatewithreplan:[18,19,21,22,23,24,25,86,157,179],navigation2:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,145,146,147,148,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,171,172,173,174,175,176,177,178,179,180,181,183,185,186,187,188],navigation2_behavior_tre:17,navigation2_dynam:15,navigation2_tutori:[15,158,166,168,171,181,183],navigation_dur:27,navigation_launch:[152,166,169,178,182,185],navigation_lifecycle_manag:150,navigation_tim:[152,161],navigation_tutori:[156,159,160],navigatior:153,navigaton2:147,navigator_plugin:161,navigatorbas:161,navsat_transform_nod:168,navthroughpos:[152,163],navtopos:152,ncancel:161,ndt:6,near_goal_dist:94,nearbi:[87,97,151,176],nearest:[94,97,181],nearli:[152,172],neccessari:[156,159,160,161,170],necess:[158,159,161],necessari:[11,23,27,94,97,129,130,143,151,153,156,158,161,166,168,169,170,171,172,173,176,178,183,187],necessarili:20,need:[2,4,11,13,22,23,24,25,27,28,43,46,49,53,79,84,87,88,89,90,94,96,97,102,105,142,143,144,146,148,151,152,153,156,157,158,159,160,161,165,166,168,169,170,171,172,173,174,175,177,178,179,180,181,183,185,186],need_recalculation_:158,neg:[104,129,130,151,157,168],negat:181,neglig:152,negoti:90,neigh:103,neighbor:[107,176],neighborhood:[94,163,165],neither:28,nest:[143,144,177],network:[11,28,143,149,152,157],neutral:184,never:[19,28,94,129,130,152,181,183],nevertheless:168,newer:[143,156,169],newest:[21,172],newli:[79,98,151,152,166,169,172,173,181,186,187],next:[4,5,19,20,22,23,24,25,28,94,104,105,125,127,143,147,149,150,156,158,159,160,161,163,165,166,168,169,170,171,176,183,186],next_target:186,nice:[28,156],no_inform:[110,114,176],no_readings_timeout:111,no_valid_control:[71,72,153],no_valid_rout:173,node:[0,17,18,19,21,22,23,24,25,27,29,43,46,49,51,53,55,56,58,59,60,63,69,71,72,73,75,76,77,78,79,80,81,82,85,87,88,92,101,103,104,126,129,130,141,143,149,150,156,157,159,160,161,164,165,167,168,170,171,172,175,179,180,181,182,183,185],node_:[152,156,157,158,159,160],node_nam:[92,173,177,181,183],nodebuild:157,nodeconfigur:157,nodeid:27,nodestatu:152,nois:[83,94,99,107,150,153,163,168,169,188],noisi:[151,168,176],nolint:161,nomenclatur:28,nomin:[22,24,25],non:[7,10,27,89,92,94,98,101,106,109,112,128,129,130,143,148,152,154,157,161,163,165,166,170,171,172,177,178,181,187],non_straight_penalti:[129,130],none:[27,43,46,47,48,49,53,153,161,172,173],nor:[94,178],normal:[143,152,177],notabl:144,note:[2,17,18,20,21,22,23,24,27,28,83,84,88,89,90,92,93,96,97,102,104,105,109,112,130,146,148,152,156,157,158,159,160,161,168,169,170,171,172,173,174,176,177,178,180,181,183,184,185,186,187],noteworthi:94,noth:151,notic:[94,158,168,169,171,177,186],notif:144,notifi:[92,157,161],notion:173,novel:[151,152],novelti:6,now:[11,19,20,22,23,87,147,149,150,151,152,153,154,156,157,158,159,160,161,166,168,169,170,171,172,174,177,178,179,180,184,186],nudg:163,num_attempt:23,num_coeff:175,num_cycl:26,number:[3,11,27,75,83,87,88,90,94,99,100,107,114,116,128,129,130,149,150,151,152,153,154,156,157,160,163,168,169,170,171,172,175,176,177,183,186],number_of_recoveri:161,number_of_retri:[19,20,22,23,24,25,75,86,157],number_recoveri:161,numer:153,numeric_limit:151,nutshel:28,nvidia:4,nxm:175,object:[5,10,11,27,28,78,94,148,151,152,153,154,156,158,161,167,169,171,172,184,188],observ:[110,114,144,156,159,160,161,168,169,170,187],observation_persist:[110,114,184],observation_sourc:[87,90,110,114,169,184,185],obsolet:151,obstacl:[0,1,3,9,15,18,21,28,66,79,83,87,88,90,97,107,108,114,128,129,130,131,134,148,149,152,153,163,165,166,169,170,171,179,180,184,185,188],obstacle_clearance_tim:152,obstacle_lay:[90,106,109,112,151,158,169,176,181,183,184],obstacle_max_rang:[90,110,114,151,169],obstacle_min_rang:[90,110,114,151,169],obstacle_rang:184,obstaclefootprint:115,obstaclefootprintcrit:91,obstaclelay:[90,169],obstacles_angl:87,obstaclescrit:94,obstruct:175,obtain:[7,28,29,87,150,153,168,169,175],obvious:[149,172],occasion:[28,101],occdist_scal:115,occgridload:150,occup:[6,90,93,109,110,114,163,169,182],occupancygrid:[93,112,150,153,181,183],occupi:[21,28,90,93,94,110,111,114,153,169,181],occupied_thresh:[181,183],occupied_thresh_default:93,occur:[28,99,158,185],odd:99,odom0:168,odom0_config:168,odom:[28,70,83,84,85,87,89,90,104,141,156,157,166,168,169,170,182,185],odom_dur:104,odom_fram:168,odom_frame_id:[83,87,185],odom_r:87,odom_smooth:161,odom_smoother_:161,odom_top:[85,89,104,157],odometr:[26,28],odometri:[15,18,83,85,87,89,104,118,161,167,169,170],odometry_fram:168,odomsmooth:161,off:[21,94,98,104,106,146,152,153,154,156,171,177,187],offer:[28,165,184,186],offic:1,offici:[15,142,147,166,168,169,170,171],offlin:152,offset:[170,171,173],offset_from_furthest:94,ofodom_fram:168,often:[20,28,88,152,168],old:[79,115,153,161,163],older:[89,91,97,98,147,187],omit:143,omni:[83,94,101,151,163,172,185],omnidirect:[83,94,98,101,152,163,165,168,172,187],omnimotionmodel:83,ompl:3,on_abort:157,on_activ:[28,156,159,160,161],on_cancel:157,on_cleanup:[156,159,160,161],on_complet:152,on_configur:[28,156,159,160,161],on_deactiv:[156,159,160,161],on_parameter_event_callback:152,on_success:157,on_tick:157,on_wait_for_result:[152,157],on_xyz:161,onactioncomplet:156,onc:[13,19,20,23,70,81,83,87,92,94,98,128,129,130,142,143,144,146,147,150,151,152,154,161,169,170,171,177,178,180,185,187],oncleanup:156,onconfigur:156,oncreatecommand:143,oncycleupd:156,one:[3,5,7,8,11,14,19,27,28,74,78,87,88,92,94,99,130,143,144,150,151,152,154,157,158,161,165,168,169,170,171,172,173,175,176,177,178,179,180,181,183,185,186,187],ones:[18,129,130,152,165,169],onfootprintchang:158,ongo:27,ongoalposereceiv:161,oniniti:158,onli:[0,3,9,11,19,20,21,28,41,42,51,75,81,83,87,88,90,94,100,109,129,130,139,143,148,149,150,151,153,154,156,157,158,160,163,164,166,167,168,169,170,171,172,174,176,177,178,181,182,186,187],onlin:[27,152],online_async_launch:[169,182],onloop:161,onpreempt:161,onrun:156,onto:[19,22,24,94,98,152,161,163,168,170,187],open:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,129,130,141,143,144,146,158,166,168,169,170,171,172,175,177,178,179,180,181,182,183,184,186],open_loop:104,opencl:7,openmp:7,openvdb:184,oper:[4,5,22,24,25,28,87,88,94,97,104,106,144,147,148,151,152,153,156,158,159,160,161,165,168,169,170,172,173,175,185,186],operandi:187,opinion:172,opportun:[22,24,25,154,157,161],oppos:[28,130],opposit:[92,130,154,170,181],opt:[142,147,168,171,180,182],optim:[3,18,23,28,88,94,101,109,128,143,151,152,153,163,165,166,172,173,175,187],optimi:172,option:[2,3,6,9,41,42,83,87,88,94,129,144,151,152,153,158,169,171,174,175,176,177,178,179,184,186],options1:171,orang:186,orbit:171,orchestr:[17,148,177,186],order:[1,11,28,90,92,94,105,112,149,151,152,157,158,159,161,166,168,169,171,172,173,174,175,181,183,186],ordinari:90,org:[15,146,150,171,172],organ:[14,142,143,159,160,186],organiz:23,orient:[55,56,88,94,95,97,99,103,122,128,129,130,139,147,154,158,160,165,168,169,180,181,182,183],orientaton:152,origin:[2,5,6,8,14,27,55,56,78,87,88,90,128,129,130,145,150,151,166,168,169,171,174,181,183],origin_i:90,origin_x:90,origin_z:[90,114,169,184],oscil:[91,99,100,135],oscillation_reset_angl:135,oscillation_reset_dist:135,oscillation_reset_tim:135,oscillationcrit:91,ost:175,other:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,19,20,23,59,61,87,94,97,99,104,109,143,144,146,147,148,151,152,153,154,156,157,159,160,161,163,165,166,167,168,169,170,171,173,174,175,176,177,178,179,181,183,184,186,187],otherwis:[4,20,58,61,64,65,66,67,68,71,72,73,83,94,99,111,130,151,152,163,168,172,173,183],our:[0,11,14,16,28,93,130,143,144,146,152,156,157,158,159,160,161,165,168,169,170,171,173,176,177,178,179,181,183,184,185,186],ourselv:170,out:[0,1,9,13,14,20,21,22,27,28,79,85,86,87,94,99,104,128,129,130,143,146,150,151,152,153,156,159,160,161,163,168,169,170,172,177,178,181,185,186,187],outcom:94,outdat:88,outdoor:106,outermost:87,outlin:[19,21,151,166,170],output:[1,2,3,4,5,6,7,8,9,10,11,12,13,28,87,94,128,129,130,148,151,152,157,158,165,168,169,170,171,173,174,177,178,181,183,185,186],output_go:[21,22,51,78,179],output_path:[21,55,56,179],output_port:186,output_typ:169,outsid:[87,98,152,153,179,187],over:[5,6,8,11,14,19,21,27,28,51,82,87,94,131,146,148,151,152,153,161,165,168,169,172,173,175,181,184,185,187],overal:[7,19,74,165,169],overcam:152,overcom:94,overhead:11,overlai:[143,144],overlaid:28,overlay_mixin:142,overli:94,overrid:[90,93,115,143,152,156,157,158,159,160,161],overridden:[84,89,90,93,96,150,151,157,158],overriden:153,overrod:87,overshoot:[94,97,151],overview:[101,144,168,170],overwhelm:19,overwrit:[93,110,114],overwritten:[85,110,114,152],owen:163,own:[11,18,28,83,87,101,143,146,148,149,150,151,156,157,158,159,160,161,163,165,168,169,170,171,172,173,178,181,182,183,185],ownership:146,pablo:163,packag:[5,8,17,18,27,28,86,87,90,94,97,98,101,104,130,141,142,143,146,147,151,152,153,156,157,158,159,160,161,167,168,169,170,171,172,173,174,175,176,177,178,179,181,183,185,187],pad:90,padmanabhan:163,page:[0,2,3,8,28,89,101,106,109,112,151,153,174,176,181,183],pai:172,pain:[170,177],pair:[19,20,94,100,112,151,154,172,175,181,183,187],palett:[143,144,186],pan:152,pancak:186,pane:[171,183],panel:[2,101,171,186],paper:[97,148,159],par:172,parabol:103,parallel:[7,13,185],param:[28,98,151,158,168,171,172,177,178,181,183,185],param_rewrit:[181,183],param_substitut:[181,183],param_tol:88,paramet:[2,13,19,20,26,28,29,47,48,65,77,80,82,91,143,149,150,156,157,158,159,160,161,165,166,168,169,171,172,173,174,175,176,177,178,180,181,183,185,186,187],parameter:[152,184,186],parameter_ev:168,parameterev:[152,168],parameteriz:186,parametervalu:[158,159,160],paramlog:152,params_fil:[156,159,160,161,166,172,181,183],paremet:153,parent:[19,20,70,143,151,156,158,159,160,168,169,170,171,177],parent_nod:161,parma:160,pars:[2,28,143],parser:175,part:[28,32,33,35,36,37,55,56,83,87,101,109,146,150,152,158,165,166,169,171,174],partial:152,particip:[11,146],particl:[6,7,28,83,147,163,172,176],particlecloud:150,particular:[6,20,23,28,94,150,152,161,174,177,178],particularli:[28,99,143,169,181],pass:[21,22,24,25,43,46,49,51,69,90,92,94,98,115,131,142,152,163,178,179,181,187],passabl:151,passag:[129,130],passibl:181,passthrough:144,past:[14,166,168,169,171,184],patch:[144,146],path:[3,4,18,19,20,21,22,23,24,27,28,29,41,42,45,47,48,52,55,56,66,68,77,79,85,86,88,89,93,95,96,97,98,99,100,101,102,103,115,126,128,129,130,131,136,137,141,142,143,148,150,151,156,157,158,159,160,161,163,165,166,168,169,171,172,174,176,177,178,179,180,181,183,186,187],path_blackboard_id:[85,161],path_blackboard_id_:161,path_distance_bia:115,path_downsampling_factor:88,path_loc:56,path_resolut:94,path_upsampling_factor:88,pathalign:[91,115],pathaligncrit:[91,94],pathanglecrit:94,pathdist:[91,115],pathdistcrit:91,pathexpiringtim:[25,86,152],pathfind:166,pathfollowcrit:94,pathlongeronapproach:[23,86,163],patienc:153,patience_exceed:[71,153],patrol:[27,28],pattern:[19,20,175],paus:[18,127,147,149,151,152,153],payload:183,pdf:169,penal:[94,154],penalis:103,penalti:[94,129,130,138,152,172],pencil:181,pend:[28,161],peopl:[4,9,22,24,25,87,167],pepper:[153,176],per:[87,94,146,158,159,160,163,164,165,166,178],perceiv:[28,169],percent:[112,181,183],percentag:[65,83,111,112,159,163,178,181],percept:[10,28,148,163,167,169,175,184],perf:143,perfectli:[94,187],perform:[1,3,4,7,9,11,18,23,27,29,31,44,54,83,87,88,94,101,105,129,130,143,148,151,152,153,156,157,158,159,160,166,169,172,173,176,177,179,186],perhap:186,period:[19,86,88,143,149,152,158,161,163],permiss:28,permit:[4,146,181],perpetu:172,persist:[143,163],person:[21,23,27,143,146,179],perspect:87,perturb:[94,172],pf_err:83,pf_z:83,pgm:[181,183],phase:[3,6,130],phi:111,phone:156,photo:[126,151,163],photoatwaypoint:[105,151,163],physic:[98,167,168,169,172,177,178,182,184,187,188],pick:[5,27,28,105,180],pictur:[27,28,105,158,181,183,185],pid:[143,178],piec:170,pipe:[20,153],pipelin:[163,175],pipelinesequ:[18,19,21,22,23,24,25,86,157,179],pitch:[168,172],pivot:172,pixel:[28,90,176,181],pkg:[85,152,154,161,168,171,177,178,180],pkg_share:[168,169,171],pkg_share_dir:161,place:[13,27,28,54,90,97,98,110,114,128,130,146,151,152,153,154,156,158,159,160,161,163,165,171,174,175,176,181,183,185,187],placehold:161,plai:[28,166],plan:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],planar:[168,169],plane:[152,168,171],planned_footprint:129,planner:[1,2,4,9,10,17,18,19,20,22,23,24,25,29,41,42,49,72,87,88,90,94,97,98,99,100,104,109,118,136,137,148,149,150,156,158,162,164,166,167,173,174,179,181,184,187],planner_id:[19,21,22,23,24,25,27,41,42,49,86,157,174,179],planner_plugin:[95,96,103,128,129,130,150,165],planner_selector:49,planner_serv:[92,95,96,103,128,129,130,151,160,165,173],plannerselector:[22,24,25,86,151],plannerserv:152,plate:156,platform:[7,94,101,148,151,167,170,172,186,187],pleas:[0,2,3,14,20,27,28,87,89,97,106,109,112,146,148,150,156,158,163,165,166,169,170,172,174,176,177,180,181,182,183,184,185,186],plot:180,plu:[168,169],plugin:[1,5,11,12,13,17,18,20,27,28,41,42,45,52,83,85,88,94,95,97,98,99,100,102,103,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,147,148,164,166,167,171,173,176,178,179,181,183,185,186,187,188],plugin_id:[159,160,161],plugin_lib_nam:[85,157],plugin_nam:[158,160,184],plugin_name_:159,plugin_specific_paramet:[159,160,161],plugin_typ:[158,160,184],pluginlib:[3,28,149,156,158,159,160,161,174,184],pluginlib_export_class:[156,158,159,160,161],pluginlib_export_plugin_description_fil:[156,158,159,160,161],pluse:151,png:[126,151,181,183],pocket:94,point:[4,9,10,14,18,19,20,22,23,24,25,27,28,51,87,88,90,94,95,97,98,99,100,103,105,106,109,115,128,129,130,132,134,136,146,148,150,151,152,153,154,158,159,160,161,163,166,168,169,170,171,172,173,175,177,180,184,185,186,187],pointcloud2:[87,90,110,114,184,185],pointcloud:[87,90,153,169,184],pointcloudcutoff:169,pointcloudcutoffmax:169,pointcost:27,pointer:[151,152,156,157,158,159,160],polici:[94,169,171],poll:27,polygon:[27,153,166,185],polygon_limit:87,polygon_nam:87,polygon_pub_top:[87,185],polygon_slowdown:[87,185],polygon_stop:[87,185],polygon_sub_top:87,polygonlimit:87,polygonslow:[87,185],polygonstop:[87,185],pool:94,poor:28,pop:177,popul:[7,83,85,151,152,156,161,169,173,174],popular:[28,172,177],port:[17,20,85,146,150,151,152,157,169,174,179,186],portion:[19,89,174],portslist:157,pose2d:83,pose:[18,20,21,27,28,41,42,47,55,56,61,63,78,83,88,94,95,97,103,120,122,124,128,129,130,132,133,141,147,148,149,150,151,152,158,159,160,161,163,168,169,171,172,179,182,185],posearrai:150,poseprogresscheck:[89,163],posestamp:[27,41,42,47,48,51,56,78,151,152,159,160,161,173,182],posewithcovari:168,posewithcovariancestamp:168,posit:[1,4,56,87,89,122,147,149,151,152,157,158,159,160,161,168,169,170,171,172,176,179,180,182],possibl:[2,14,17,28,84,94,97,143,148,151,152,153,159,161,165,166,172,176,177,181,183,185],post:[0,14,83,87,106,109,112,129,130,146,174],postcreatecommand:143,potenti:[0,1,6,7,9,10,28,87,97,128,129,130,148,151,152,153,163,169,176,177,178],power:[4,19,88,94,144,152,172],power_supply_statu:64,power_supply_status_charg:64,pr2441:152,pr2454:152,pr2456:152,pr2459:152,pr2469:152,pr2479:152,pr2480:152,pr2483:152,pr2489:152,pr2993:152,practic:[143,146,151,156,158,159,160,161,170,172,181,185],pradheep:163,pre:[10,61,84,85,86,93,94,97,130,143,163,180,181,187],prebuild:143,precis:[28,151,166],precise_goal_check:[45,46,151],precompil:143,precomput:152,predefin:28,predict:[29,87,151,154,163],prediction_horizon_:94,predomin:146,preeemption:161,preempt:[19,21,27,150,157,161,163],preemption:[22,24,157,161],preemptiv:[143,154],prefer:[0,28,93,98,104,109,129,130,143,144,147,151,152,154,163,171,172,178,181,187],preferenti:94,preferforwardcrit:[91,94],preferr:171,prefix:[156,158,159,160,161,171,177,178,180],prepar:[168,171,173],prerequisit:[23,145,169],presenc:[4,94,172,181],present:[23,104,110,114,143,150,152,153,154,158,159,161,163,169,172,185],preset:185,press:175,presum:92,pretti:[169,170,172],prevent:[9,19,28,30,83,87,88,94,97,104,110,114,129,130,135,140,143,151,152,153,154,163,172,173,176,181],preview:2,previou:[20,25,94,146,151,153,154,158,161,163,166,168,169,171,172,183,184],previous:[13,151,152,153,154,159,161,169,177,178],primari:[1,6,19,98,99,152,169,171,173],primarili:[19,152,166,172],primary_control:[98,187],prime:172,primit:[26,28,129,130,152,171],princip:[158,175,183],principl:181,print:[27,88,152,177],printenv:141,prior:[20,79,83,149,152],priorit:152,prioriti:[87,146,153,161,173],privat:14,privileg:[143,144],probabalist:163,probabilist:150,probabl:[21,93,111,153,169,174],probe:[20,143],problem:[23,50,92,152,160,161,163,172,177],problemat:[88,97,177],proccess:177,proce:[161,171],proceed:93,process:[5,7,8,11,23,27,28,29,52,83,85,89,90,94,96,97,99,129,130,142,143,145,147,150,151,153,156,157,161,163,167,171,172,173,176,177,178,184,186,187],processor:[7,94,172],produc:[4,28,87,94,152,153,156,160,165,169,172],product:[9,28,132,133,136,137,143,144,148],profession:[22,24,25,148],profil:[1,2,3,4,5,6,7,8,9,10,11,12,13,94,177,188],program:[2,17,27,28,101,129,130,143,152,177,178,179],progress:[4,67,89,94,97,121,123,143,146,153,164,172,187],progress_check:[89,91,97,98,187],progress_checker_id:153,progress_checker_plugin:[89,91,97,98,150,187],progress_checker_plugin_id:[121,123],progresscheck:150,project:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,18,28,84,87,94,97,120,142,143,144,146,148,152,158,164,166,168,169,170,171,173,176,181,183,185,186,187],project_nam:[168,169,171],projection_tim:84,promis:152,promot:20,prompt:[2,144,177],prone:28,proof:28,proper:[88,170,171],properli:[9,27,131,152,166,167,168,169,170,171,176,181,183],properti:[20,87,143,168,169],propig:173,proport:[20,94,129,130,181,184],proportion:[104,159],propos:[0,6,150,151,152],proprtion:94,protect:146,provenli:28,provid:[2,4,7,11,17,18,19,20,22,24,25,27,28,29,43,46,49,53,58,83,85,86,87,90,93,94,99,104,110,114,136,137,142,143,144,146,147,148,152,153,156,157,158,159,160,161,164,165,167,168,169,170,171,172,173,174,176,177,179,180,182,186],providedbasicport:157,providedport:157,prox_len:[23,79],proxim:[23,51,79,94,97,151,152,185],prudent:144,prune:[94,115,143,154],prune_dist:[94,115,153],prune_plan:115,psutil:152,pub:182,publish:[21,43,46,49,53,83,85,87,89,90,91,93,94,104,106,109,112,114,115,125,129,147,149,150,151,152,154,156,159,161,163,166,168,169,172,174,175,179,180,182,185],publish_acceler:168,publish_cost_grid_pc:118,publish_evalu:118,publish_frequ:[90,169],publish_global_plan:118,publish_local_plan:118,publish_odom:168,publish_odom_tf:168,publish_tf:168,publish_trajectori:118,publish_transformed_plan:118,publish_voxel_map:[90,114,169,184],publish_wheel_tf:168,published_footprint:[84,87,99,100,102,156,166,174],publishfeedback:161,pull:[14,142,143,144,146,150,151,152,163,172,177,186],pure:[29,94,148,151,152,153,156,158,160,161,163,165,172,187],pure_pursuit_controller_plugin:159,purepursuitcontrol:159,purpl:88,purpos:[10,28,146,148,153,157,161,165,171,179,182,183],pursuit:[29,148,151,152,163,165,172,187],push:[88,143,146,164],push_back:160,put:[11,88,152,158,163,171,173,185],pycostmap2d:27,python3:[2,12,13,27,148,151,152,153],python:[4,10,148,151,168,181,183],qualifi:83,qualiti:[3,8,26,28,88,94,100,101,129,130,146,148,152,168],quaternion:[151,168,170],queri:[151,152,163,165],question:[0,146],queue:146,quick:[19,129,130,170,181],quickli:[7,143,146,152,170,186],quirk:[152,172,187],quit:[20,144,152,177],r8g8b8:169,race:143,rad:[84,89,94,97,98,117,121,122,124,135,139,187],radar:[28,168,169,184],radar_msg:169,radial:175,radian:[54,83,87,94,97,98,187],radii:[94,97],radiu:[22,51,87,88,90,94,97,108,121,123,129,130,131,152,163,165,166,169,171],ragged:28,rai:[7,169],rais:177,random:[83,153],randomli:[94,172],rang:[4,7,65,83,87,90,97,110,112,114,143,150,151,163,164,171,173,176,177,181,183,185],ranger:169,rangesensorlay:150,rare:[150,152],raster:[181,183],rate:[9,12,19,20,77,80,82,83,87,104,105,110,114,149,151,156,163,171,179],ratecontrol:[19,21,22,23,24,25,86,157,179],rather:[17,20,22,24,25,28,83,88,90,143,149,150,151,152,154,161,163,170,172,177,182],ratio:[129,130,171,175],raw:[84,102,148,174,177,181,183],raycast:[110,114,163],raytrac:[110,114,151,169],raytrace_max_rang:[90,110,114,151,169],raytrace_min_rang:[90,110,114,151,169],raytrace_rang:151,rcl_interfac:[152,168],rclcpp:[11,158,159,160,161],rclcpp_action:161,rclcpp_compon:173,rclcpp_error:[160,161],rclcpp_info:[156,160,161],rclcpp_lifecycl:[159,161],rclcpp_node:152,rclcpp_node_:152,rclcpp_warn:[157,161],rclpy:[27,152],reach:[0,14,19,20,23,89,94,122,124,127,128,158,159,163],react:[152,171],reaction:19,reactiv:[22,24,179],reactivefallback:[19,20,22,23,24,25,86,157],reactivesequ:[22,23,25],read:[6,8,19,28,87,111,144,151,152,163,169,177,181,183],readabl:171,reader:[167,187],readi:[23,142,143,146,147,152,158,171,172,177,181,183,185],readili:142,readm:[17,87,94,97,98,101,103,104,150,151,152,153,172],real:[4,9,12,28,87,146,168,169,170,171,175,179],realist:12,realiti:28,realli:[28,88,172,181],rearrang:17,reason:[6,28,87,94,128,129,130,146,152,158,161,166,170,172,177,185],reattempt:[22,24,25],rebuild:177,rebuilt:143,recal:[20,169],recalcul:158,receiv:[19,20,27,28,43,46,49,53,78,89,98,101,104,111,113,150,152,153,156,159,161,163,168,169,170,172,179,187],recent:[9,51,147,172],recharg:[19,28],reckon:28,recogn:176,recomend:152,recommend:[1,2,3,4,5,6,7,9,10,12,28,87,92,94,97,99,100,143,146,147,159,165,166,168,169,170,171,172,174,180,182,184,186,187],recompil:[158,177],recomput:19,reconfigur:[13,18,151,152,165,173],reconnect:92,record:146,recov:[19,83,92],recoveri:[2,18,22,23,24,25,30,31,54,57,75,84,85,86,148,149,150,153,156,157,161,163,174],recoveries_serv:[152,156],recovery_alpha_fast:83,recovery_alpha_slow:83,recovery_count:161,recovery_plugin:[150,152,156],recovery_serv:152,recoveryact:[19,22,23,24,25,86,157],recoveryfallback:[19,22,23,24,25,86,157],recoverynod:[19,20,22,23,24,25,86,157],recreat:143,rectangular:[88,166],rectifi:28,recurs:[99,100,129,130],red:174,redd:129,redesign:14,redistribut:146,reduc:[0,28,94,97,99,100,104,130,143,146,149,150,151,153,173],reduct:150,redund:150,reed:[88,129,130,151,152,163,165],reeds_shepp:129,reedshepp:152,ref:[1,2,3,4,5,6,7,8,9,10,11,12,13],refactor:[146,149],refer:[3,19,28,51,59,61,77,84,85,87,89,90,97,99,101,106,109,112,142,143,144,149,150,152,153,156,157,158,159,160,161,165,166,167,168,169,170,171,176,179,181,183,185,186],referenc:[158,168,169,185],refin:[28,88,100,129,130,147,152],refinement_num:[99,100,129,130,153],reflect:[143,151,154,169,171],refus:94,regard:[0,20,152,161,171,172],regardless:[87,104,144,158,168,178],regim:[94,172],region:[39,94,148,163],regist:[28,86,156,157,158,159,160,161,169,184],registerbuild:157,registr:184,registri:[142,143],regul:[29,148,151,152,159,163,165,172,187],regular:[28,30],regularli:165,regulated_linear_scaling_min_radiu:97,regulated_linear_scaling_min_spe:97,regulatedpurepursuitcontrol:[97,98],rehash:153,reimplement:[5,6],reinit:163,reiniti:163,reinitialize_global_loc:50,reinitializegloballoc:86,reject:[129,130,152,161],rel:[8,28,56,87,90,94,104,150,154,165,166,168,170,172,178],relat:[4,11,13,14,26,28,87,106,107,109,112,142,143,148,151,152,167,170,171],relationship:[94,170],relav:156,relax:143,releas:[27,149,150,164,184],relev:[1,2,3,4,5,6,7,8,9,10,11,12,13,19,148,149,157,161],reli:177,reliabl:[6,12,17,43,46,49,53,144,148,169,171],reloc:50,relwithdebinfo:178,remain:[13,19,20,21,28,88,94,118,143,144,149,150,151,152,156,157,158,159,160,176,187],remaind:28,remap:[32,33,34,35,36,37,41,42,45,151,152,168,169,173,174,177,178,179,185],rememb:[14,97,141,143,170,171],remot:[143,144,156,157,177],remote_containers_ipc:143,remote_containers_socket:143,remov:[11,21,22,51,55,56,93,99,107,110,114,143,149,150,163,168,169,174,176,177,178,184,186,187],removepassedgo:[22,86,151],renam:[84,143,150,151,152],renavig:19,render:144,reopen:144,rep145:168,rep:[28,148,151,164,168,170],repeat:[26,94,142,158,170,171],repeatedli:[181,183],repetit:[153,171],replac:[4,5,10,11,17,85,88,149,152,153,154,156,158,160,161,172,174,176,182,184,185],replan:[18,20,21,22,24,51,77,82,86,115,129,130,150,151,172,179],replic:143,repo:[12,28,103,142,144,179,184],report:[12,83,94,146,151,153,157,169],repositori:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,97,142,143,144,148,156,158,159,160,164,166,168,169,171,172,181,183,184],repres:[10,12,19,28,94,97,148,151,159,164,168,169,171,177],represent:[10,90,148,165,169,170],reproduc:[142,143],repuls:94,repulsion_weight:94,reput:8,request:[11,14,19,21,27,28,84,85,89,93,94,95,96,98,102,128,129,130,143,144,146,150,151,152,153,154,156,157,161,163,172,173,174,177,182,183,186,187],requir:[1,2,3,4,5,6,7,8,9,10,11,12,13,21,28,83,88,92,94,98,103,104,112,143,146,151,152,153,154,165,168,169,170,171,172,173,177,179,184,187],required_movement_angl:[121,153],required_movement_radiu:[89,91,97,98,121,123,187],rerun:143,resampl:83,resample_interv:83,research:[9,14,28],resembl:20,reserv:[22,24,25,153,173],reset:[68,83,94,135,147,150,151,152,157,158,161,163],reset_dist:[38,39,151],reset_period:94,resolut:[27,90,94,114,128,129,130,151,158,163,165,166,169,180,181,183],resolv:[22,24,25,92,150,152,174,184],resour:160,resourc:[27,28,84,94,102,143,152,153,156,159,161,166,167,168,170,172,173,178,181,184],respawn:[92,172,185],respawn_delai:185,respect:[4,28,98,109,151,152,157,164,165,168,169,171,172,184,187],respond:[0,173],respons:[20,22,24,25,28,38,39,40,87,92,152,156,161,165,173],rest:[19,38,39,94,126,144,154,168,169,170,173,178],restart:143,restrict:[28,87,112,151,153,154,163,172,183],result:[9,17,20,27,28,55,56,78,88,94,97,99,100,103,105,146,150,151,156,157,158,161,163,172,173,175,176,186,187],resultstatu:156,resum:153,retain:[20,60,99,100,128,129,130],retick:20,retrain:4,retransit:152,retreiv:10,retri:[18,22,24,25,75,163],retriev:[159,160,161],retrospect:152,retrospective_penalti:[129,130],retry_attempt_limit:94,retryuntilsuccesful:23,retryuntilsuccess:23,retryuntilsucessful:23,retun:[94,152,172],reus:[28,143,156,171,173],revers:[88,94,97,101,104,129,130,152,154,173,183],reverse_penalti:[129,130],reversing_en:88,revert:177,review:[0,13,143,144,146,161,172],revisit:[144,153],rewrittenyaml:[151,181,183],rfid:27,rgb:169,rgba:171,rgbd:9,rich:28,right:[28,94,103,104,129,130,146,147,152,168,170,175,176,178],right_joint:168,right_wheel_est_vel:168,righthand:126,rigid:[171,172],rise:88,roam:166,robbin:76,robin:[20,163],robocup:179,robot:[1,2,4,5,6,7,8,9,10,12,13,14,19,20,21,22,23,24,25,26,27,28,31,38,39,44,50,51,55,56,59,61,67,77,79,82,83,84,85,87,88,89,90,94,97,98,101,102,104,105,106,109,110,112,114,121,122,123,124,125,127,128,129,130,131,132,133,134,135,136,138,139,140,144,147,148,149,150,151,153,158,159,160,161,163,165,169,170,173,174,176,177,178,179,180,181,183,184,185,186,187],robot_base_fram:[51,59,61,77,84,85,90,99,100,102,156,157,158,161,168,169,174],robot_descript:[168,171],robot_fram:56,robot_loc:[15,168,170],robot_localization_nod:168,robot_model_typ:[83,152],robot_nam:172,robot_navig:27,robot_radiu:[90,158,166,169,172],robot_sdf:172,robot_state_publish:[169,170,171],robot_state_publisher_nod:[168,171],robotech:88,roboticist:28,robotmodel1:171,robotmodel:171,robust:[4,6,28,186],rocker:144,role:[14,28,157,161,165,166,177],roll:[84,90,93,94,141,143,164,168,172,186],rolling_window:[90,169],room:[10,94,180,181,183],root:[18,19,20,21,22,23,24,25,26,86,142,143,144,152,156,157,159,160,161,168,169,171,179,186],root_kei:[181,183],ros1:[148,150,151,169],ros2:[141,147,152,156,158,159,160,161,166,168,169,170,171,175,176,177,178,179,180,181,182,183,184,185],ros2_control:168,ros:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188],ros__paramet:[59,61,83,84,85,87,88,89,90,91,92,93,94,95,96,97,98,99,100,102,103,104,105,106,107,109,112,128,129,130,150,151,154,156,157,159,160,161,165,168,169,174,176,181,183,184,185,187],ros_distro:142,ros_w:142,roscon:[1,182,184],rosdep:[141,142,143],rosdistro:141,rosout:168,rot_stopped_veloc:124,rotat:[27,28,29,54,83,84,88,94,97,104,117,121,122,128,130,139,153,159,163,164,165,168,170,171,188],rotate_to_heading_angular_vel:[97,98,187],rotate_to_heading_min_angl:97,rotatetogo:91,rotatetogoalcrit:91,rotation_penalti:130,rotational_acc_lim:[84,156],rotationshimcontrol:[98,187],rough:[97,98,152,171,172,187],roughli:[94,101,147],round:[20,76,87,163,167],roundrobin:[19,22,23,24,25,86],rout:[3,10,27,28,94,161,164,172,173],route_error_code_id:173,route_id:173,route_msg:173,route_serv:173,route_tim:173,routeserv:173,rpp:[165,172,187],rpy:[169,171],rsj:148,rst:163,ruffin:[14,143,148],ruffsl:14,rule:[10,28,159,160,170],run:[0,3,4,7,9,14,17,20,27,28,74,77,80,82,83,84,89,92,93,94,101,126,129,130,141,142,143,144,146,150,151,152,163,165,167,170,172,173,175,177,178,180,182,185,186],runarg:143,runtim:[28,151,152,156,157,158,159,160,161,184],rviz2:[161,171,180],rviz:[17,147,158,159,160,161,167,168,172,176,182,183,186],rviz_common:171,rviz_config_fil:172,rviz_default_plugin:171,rviz_nod:[168,171],rvizconfig:171,ryzhikov:163,safe:[9,13,28,97,148,151,156,157,165,169,170,172],safer:9,safeti:[0,1,28,87,92,149,150,151,163,164,172,181,182,185],sai:[11,19,20,28,146,177],said:165,sake:19,salt:[153,176],sam_bot:[166,168,169,171],sam_bot_descript:[166,168,169,171],sambot:166,same:[11,17,19,27,28,60,62,83,85,87,88,94,97,104,129,130,143,144,146,147,149,150,152,153,154,156,158,161,169,171,172,173,177,178,181,183,184,185,187],sampl:[6,28,94,98,116,126,153,154,165,166,168,169,172,179],samsung:14,san:14,sandbox:182,sarthak:163,satisfact:94,satisfi:168,sausag:144,save:[83,93,126,129,130,150,151,152,163,166,171,172,175,179,181,182,183,186],save_images_dir:126,save_map:150,save_map_timeout:[93,151],save_pose_r:83,saver:[29,106,109,112,151,181,183],savitzki:[29,163],savitzky_golay_smooth:99,savitzkygolaysmooth:99,scalabl:28,scale:[9,28,91,94,97,99,115,131,132,133,134,135,136,137,138,139,140,151,163,170,171,172,181,183,185],scale_veloc:104,scaling_spe:115,scan:[6,9,27,83,87,90,163,169,170,185],scan_top:[83,169],scanner:[6,87,110,114,169,185],scenario:[19,23,165],scene:[28,94,149],schema:[142,143],scheme:[8,169],school:28,scope:[4,143,168,169,179,185],score:[94,115,131,132,133,134,136,137,138,165,172],scratch:143,screen:[152,156,168,169,171,173,177,178,181,183,185,186],script:[93,143,153,163,181,183,185],sdf:[152,168,169],sdl:149,se2:[94,109,129,130,148,152,163,172],search:[28,56,94,97,98,101,115,128,129,130,141,151,152,165,172,187],sec:[82,157,182],seccomp:143,second:[9,19,20,22,24,25,28,30,31,44,52,54,68,69,74,75,79,85,87,89,92,93,94,98,125,126,128,129,130,151,152,157,163,168,169,170,173,175,176,181,183],section:[18,19,28,88,94,145,146,148,152,154,158,163,165,166,167,168,169,170,171,172,173,176,177,183],secur:[27,28,143,145],see:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,17,19,20,23,28,30,31,41,42,44,45,52,54,66,85,87,88,91,94,97,98,101,103,104,110,114,130,141,142,146,147,148,150,151,152,153,154,158,159,160,161,163,164,165,166,168,169,170,171,172,173,174,175,177,178,179,180,181,182,183,184,186,187],seek:[7,148],seem:94,seen:[18,23,101,152,157,158,168,173,186],segment:[88,94,99,143,165,166,169,174,176],select:[2,3,5,7,18,28,43,46,49,53,83,87,94,95,97,98,103,106,107,108,109,110,111,112,113,114,128,129,130,143,144,151,153,157,158,163,166,167,169,171,174,176,177,178,179,181,183,186,187],selected_control:43,selected_goal_check:46,selected_plann:49,selected_smooth:53,selector:[22,24,25,163],self:[142,144],self_client_:161,semant:[0,27,148,151,170,173],send:[0,9,27,89,90,97,104,152,156,157,161,179],send_goal:156,send_messag:156,send_sm:156,sendsm:156,senior:146,sens:[170,184,186],sensibl:109,sensit:[6,106,153],sensor:[1,5,7,9,22,24,25,28,87,90,110,114,143,148,150,151,153,163,165,166,167,168,170,171,172,173,176,184,185],sensor_driv:173,sensor_fram:[110,114,171],sensor_msg:[64,65,87,168],sensorplugin:168,sent:[63,104,152,153,156,161,179],sentin:161,separ:[17,28,87,90,94,109,143,148,151,152,158,168,170,173,177,178,181,182,186],separet:154,seper:[174,177],sequenc:[19,20,21,22,23,24,25,26,86,94,143,153,163,168,173,174,179],sequencestar:[23,157],sequenti:148,seri:[166,168,177],seriou:[172,177],serious:146,serv:[19,23,148,152,169],server:[10,11,13,17,18,19,20,23,27,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,52,53,54,57,71,72,73,79,83,85,90,91,92,94,99,100,105,106,109,112,115,116,117,118,119,120,121,122,123,124,131,132,133,134,135,138,139,140,141,147,148,149,151,156,157,158,159,160,161,163,164,168,172,174,177,178,184,185,186,187,188],server_nam:[30,31,32,33,34,35,36,37,41,42,44,45,47,48,54,57,151],server_timeout:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,54,57,66,85,151],servic:[20,28,32,33,34,35,36,37,38,39,40,50,83,93,97,143,144,148,150,151,153,156,163,165,168,175],service_nam:[19,22,23,24,25,32,33,34,35,36,37,38,39,40,50,86,157],servicet:152,session:[128,129,130,143,177],set:[1,2,3,9,10,13,17,18,22,24,25,27,28,30,31,41,42,44,45,52,54,56,58,65,83,88,89,90,92,93,94,95,97,101,103,104,105,106,110,112,113,114,115,128,129,130,141,142,143,144,146,147,148,150,151,152,153,154,156,157,158,159,160,161,163,167,172,173,174,175,177,178,179,180,181,182,183,184,185,187],set_camera_info:175,set_initial_pos:83,set_pos:168,setcost:27,setcostmap:27,setinitialpos:[27,152],setplan:159,setspeedlimit:159,setup:[2,28,141,142,143,144,147,158,166,169,170,171,172,173,177,181,182,183,185],sever:[17,50,86,87,94,101,143,146,151],shadow:180,shape:[87,101,148,153,165,166,167,171,172,181,183,185],share:[11,28,84,85,87,102,143,147,152,154,156,158,159,160,161,168,169,171,172,180,187],shared_ptr:[152,156,159,161],sharedptr:[152,161],sharp:[154,172],sharper:97,sheep:[129,130,152],shelf:27,shell:143,shelv:27,shepp:[88,129,151,163,165],shift:[143,144],shim:[29,163,164,172,188],ship:[16,27],shoot:28,short_circuit_trajectory_evalu:[91,115],shortcut:[97,129,130,152,156,158,159,160,161],shorten:153,shorten_transformed_plan:[115,153],shorter:[23,55,56,129,130,163,171,179],shortest:[28,165],should:[1,2,3,6,9,11,18,19,23,28,71,72,73,75,82,85,88,90,93,94,97,104,107,110,112,114,129,130,144,146,147,149,150,151,152,153,156,157,158,159,160,161,166,168,169,170,171,172,173,174,176,177,178,179,180,181,182,183,185,186,187],shouldn:94,shovel:28,show:[2,27,112,144,147,152,156,157,158,159,160,161,165,166,168,169,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185],shown:[13,19,27,94,146,147,151,157,161,165,166,168,169,173,174,179,183,185,186],shrijit:148,shut:[27,28,173],shutdown:[28,152,173],shuttingdown:173,sid:156,side:[26,38,39,90,94,126,143,169,171,173,176,178,186],sidebar:[146,175,178],siemen:186,sig:177,sight:[99,165],sigma_hit:83,sign:[0,104,146],signal:[9,99,163,178],signatur:[157,161],signific:[8,9,94,172],significantli:[7,9,18,23,24,25,79,94,98,152,154,163,172,187],silent:151,sim_tim:[91,119,120],simiar:170,similar:[7,9,10,20,22,24,27,28,93,94,101,142,144,151,152,157,165,168,169,171,172,174,177,184,186,187],similarli:[22,24,168],simpl:[3,28,29,99,129,130,144,146,148,149,156,157,158,160,163,165,166,170,171,172,174,177,179,182,186,187],simple_smooth:[52,100,102,174],simplegoalcheck:[45,89,91,97,98,115,151,163,187],simpleprogresscheck:[89,91,97,98,153,163,187],simpler:[170,171],simplesmooth:[53,100,102,174],simplest:157,simpli:[18,94,143,146,151,152,156,157,168,171,172,177,181,183,184,186],simplic:181,simplifi:[6,147,150,157,159,161,177],simul:[1,2,3,4,5,6,7,9,10,11,12,13,17,85,87,94,98,119,120,141,147,154,156,158,159,160,161,166,167,171,172,177,178,180,181,182,183,184],simulate_ahead_tim:[84,98,156,187],simulation_time_step:[84,87],simultan:[143,158,169,181,183],sinc:[6,28,88,94,97,98,100,109,129,130,151,152,158,161,165,166,167,168,169,170,171,172,173,174,177,181,183,185,186,187],singh:[97,148,163],singl:[11,17,20,22,24,25,27,28,89,93,105,146,149,150,151,152,157,158,160,163,168,169,170,171,172,173,174,177,178,184],singletrigg:[86,151],singular:172,sister:151,sit:9,situat:[1,10,19,22,24,25,28,87,97,147,148,151,152,163,166,169,172,174,177,178],size:[27,28,38,39,129,130,152,158,164,165,166,168,169,171,175,176,181,183,184],skew:175,skid:[151,165],skill:[1,2,3,4,5,6,7,8,9,10,11,12,13,177],skillset:7,skinni:172,skip:[83,94,156,168],skirt:152,slack:[0,14,28,146],slam:[6,15,90,148,149,150,169,170,172,177,180,188],slam_toolbox:[15,177,182],sleep:[87,127,157],slide:171,slider:[171,181],slight:99,slightli:[94,99,104,128,129],slop:175,slow:[83,87,94,97,112,139,151,153,154,172,177,183,185],slowdown:[87,185],slowdown_ratio:[87,185],slower:[87,176],slowing_factor:[91,139],slowli:94,smac:[29,88,94,97,98,109,151,164,165,166,187],smac_plann:97,smacplann:163,smacplanner2d:[101,128,151,163],smacplannerhybrid:[101,129,152,163],smacplannerlattic:[101,130,163],small:[94,104,129,148,150,153,161,163,164,166,168,171,172,176,180,187],smaller:[13,19,28,97,107,129,130,152,181,183],smart:[28,106],smooth:[21,27,28,52,82,88,94,98,99,100,102,104,128,129,130,148,151,152,153,163,168,172,174,187],smooth_path:[129,130],smoothed_path:[27,52,174],smoothed_path_in_collis:[73,153],smoother:[17,29,52,53,73,97,128,129,130,148,154,161,164,165,173,188],smoother_error_cod:[73,85,174],smoother_id:[27,52,174],smoother_plugin:[88,99,100,102,174],smoother_selector:53,smoother_serv:[88,99,100,102,173,174],smootherselector:86,smoothing_complet:52,smoothing_dur:52,smoothing_duration_us:52,smoothing_frequ:104,smoothing_path_error_cod:52,smoothli:[94,172],smoothpath:[27,86,88,152,174],sms:156,snippet:[19,156,159,160,161,166,168,169,171,173,177],soc:4,soccer:28,socket:144,soft:[23,94],soften:99,softwar:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,16,97,146,148,153,169,173,177],sole:[154,186],solut:[28,94,129,130,172,176],solv:[23,141,160,177],solver:[88,163],some:[4,7,11,13,18,19,20,22,27,28,43,46,47,48,49,53,94,99,101,104,109,129,143,146,149,151,152,157,159,160,161,165,166,168,169,170,171,172,176,177,179,181,186],someon:[11,14],someth:[0,19,20,27,146,152,168,170,177,181],sometim:[19,146,172,186],somewhat:[172,187],somewher:183,sonar:[28,87,153,169,184,185],soon:28,sooner:181,sourc:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,28,83,84,85,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,104,105,110,114,141,143,145,146,147,148,152,154,156,157,158,159,160,161,166,167,168,169,170,171,175,177,180,181,182,183,184,185],source_fil:[181,183],source_timeout:[87,185],space:[1,4,10,21,28,83,87,90,93,94,95,97,103,106,128,129,130,143,144,151,152,163,165,168,172,176,180,181],span:[14,148],sparingli:94,spars:[27,28,163,184],sparse_normal_choleski:88,spatial:[28,151],spatio:[163,184],spatio_temporal_voxel_lay:184,spatiotemporalvoxellay:184,spawn:[143,166,168,169],spawn_ent:[152,168],speak:178,special:[28,79,87,89,146,153,157,158,186],specif:[2,3,6,11,17,18,19,22,23,24,25,27,28,31,44,86,90,94,97,143,144,149,150,151,152,153,154,157,159,160,161,165,168,169,170,172,174,175,177,181,182,186,187],specifi:[19,22,23,24,25,27,47,48,56,65,75,85,87,90,93,126,127,130,142,143,144,150,151,152,153,157,158,159,160,163,165,168,169,170,172,175,178],speed:[2,7,9,20,26,28,31,44,82,84,87,88,89,90,93,94,97,104,109,117,128,129,130,142,143,151,152,154,159,161,163,165,172,185,188],speed_filt:[90,112,183],speed_filter_mask:183,speed_limit:[89,112,183],speed_limit_top:[89,112,183],speed_mask:183,speed_param:183,speedcontrol:[19,86,150],speedfilt:[90,112,151,183],spend:19,spent:178,sphere:[166,169,171],sphere_inertia:171,spheric:171,sphinx_doc:163,spike:[129,130,152],spin:[11,19,20,22,23,24,25,26,27,28,36,86,140,150,151,152,153,156,157,163],spin_dist:[19,22,23,24,25,26,27,54,86,157],spin_error_cod:54,spinner:11,spiral:[152,172],spiritu:148,spite:168,spline:3,split:[17,150],splitter:171,sponsor:14,spot:[22,24,25,130,147,156],squar:[26,38,39,87,90,175],src:[141,142,143,158,168,169,171,177,181,183],ssh:[143,144,177],stabil:[149,150,151,152,153,154],stabl:[97,142,143,151],stabliti:147,stack:[0,3,4,6,7,8,9,11,12,14,15,27,28,77,80,82,89,92,93,96,146,148,149,152,153,159,164,165,169,172,173,177,178,186],stage:[28,143,159],stai:[94,109,165,172,179],stale:[143,151],stall:104,stamp:[126,159,160,182],stand:[87,152],standalon:[107,153,163,176,181,183],standard:[2,6,10,83,94,146,169,170,175,181,183,186],standardtrajectorygener:[91,115],star:[29,165,172],start:[4,5,12,17,20,21,22,24,25,27,28,41,42,56,87,88,94,97,98,114,145,146,148,150,151,152,156,158,159,160,161,168,169,170,171,172,173,174,175,176,177,178,179,180,181,183,184,185,186,187],start_controller_server_nod:178,start_costmap_filter_info_server_cmd:[181,183],start_lifecycle_manager_cmd:[181,183],start_map_server_cmd:[181,183],start_sync_slam_toolbox_nod:177,start_time_:161,startup:[5,28,92,141,143,147,150,173,175,181,183],state:[3,15,17,20,22,24,25,27,60,87,88,89,91,92,94,97,98,101,104,106,122,147,150,151,152,156,157,159,160,161,163,165,166,168,169,170,172,173,182,183,186,187],state_top:[87,153],statement:146,static_lay:[90,106,109,112,158,169,176,181,183,184],static_transform_publish:[166,170],staticlay:[90,169],station:[28,165],statist:[4,9,178],statu:[18,28,146,152,156,157,181],status1:171,status:[27,161],std:[58,150,152,156,157,159,160,161,177],std_msg:[106,125,168],stddev:[168,169],stdin:177,steep:103,steeper:103,steer:[88,128,152,169,172],step:[20,28,84,87,94,169,171,177,178],step_siz:27,stereo:[87,175],steve:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,94,148,163,177],stevemacenski:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,182,184],steven:148,sticki:1,still:[19,20,27,92,97,104,109,141,143,144,151,152,153,154,168,169,171,172,177,181],stl:177,stl_vector:177,stop:[9,21,28,74,87,92,94,104,105,115,124,139,150,151,153,171,185],stop_on_failur:[105,149,151],stop_pub_timeout:[87,185],stoppedgoalcheck:[89,163],storag:[143,161],store:[83,90,110,114,143,148,153,158,159,161,169,170,178],stori:10,strace:143,strafe_theta:138,strafe_x:138,straight:[129,130,160,171,172,174],straightforward:169,strategi:146,stream:152,streamlin:[142,144],stretch:144,strictli:[6,130,153],stride:8,string:[30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,56,57,59,61,70,77,78,83,84,85,87,88,89,90,92,93,94,96,98,102,104,105,106,109,110,111,112,113,114,115,125,126,129,130,132,133,136,137,150,153,156,157,158,159,160,161,168,173,184],strive:[14,146],stroke:[2,167],strongli:28,structur:[6,8,19,28,148,153,161,165,170,171,173,183,184,186],stuck:[1,19,22,24,25,28,30,31,44,54,67,152,163,172],student:[7,146],studio:144,stutter:172,stvl:188,stvl_layer:[90,184],style:[22,24,25,172,184],sub:[0,22,24,25,152],subcommand:143,subject:[28,94,168],submit:[13,146,163],suboptim:[94,172],subproject:13,subscrib:[28,43,46,49,53,64,65,78,83,87,89,111,113,151,168,169,179],subscribe_to_upd:[90,113],subscript:[78,87,151,161,163,168,173],subsect:[143,169],subsequ:[20,28,83,143,163],subset:178,subsiqu:[129,130],substanti:[1,94,146,149,172],substitut:[85,171,179,181,183],subtleti:161,subtli:152,subtre:[18,20,22,23,24,25,28,38,39,40,86,157,163],succe:[19,20,74,75,163],succeed:[27,81,152,156,160],success:[14,19,20,23,28,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,75,94,151,152,153,156,157,163,171,176,187],successfulli:[1,19,28,152,156,161,168,170,171,173,179],successor:[94,148,153],sucessfulli:170,sudo:[142,147,168,169,171,175,178,182,184],suffici:[4,19,28,94,130,139,161,176,178],suffix:178,suggest:[20,88,94,165,170,171],suit:[0,143],suitabl:[88,98,152,163,165,170,187],sum:[83,131,132,133,134,136,137,165,171],sum_scor:[131,134],summar:[165,170,172],summari:17,summer:[5,11],superior:153,suppli:[11,28,77,80,82,85],support:[2,6,13,14,28,43,46,49,53,97,101,141,143,144,148,149,150,153,163,165,169,171,172,176,181,183,184,186],suppos:170,sure:[1,2,7,12,27,94,110,114,141,142,143,146,151,154,158,161,163,166,168,169,172,175,176,177,180,181,182,183,184,185],surfac:28,surpris:187,surround:165,survei:148,susbcrib:126,sustain:28,swap:[152,153],sweep:[171,172],symbol:177,symlink:[142,158,181,183],symmetr:154,symmetri:152,sync:186,sync_slam_toolbox_nod:177,synchron:28,syntax:[143,154,171,177],sysdep:177,system:[1,6,7,8,10,11,12,19,20,22,24,25,28,83,87,92,94,142,143,144,146,147,148,149,152,161,165,169,170,171,172,173,174,175,177,178,180],systemat:173,systemdefaultsqo:161,sysv:177,tab:[141,166,169],tabl:[152,158,159,161,167,172,173],tackl:[166,167],tag:[142,143,152,157,168,169,171],tailor:165,take:[1,9,12,17,18,22,23,27,28,41,42,45,47,48,61,79,83,87,89,92,94,96,98,99,100,105,126,128,143,146,147,149,151,152,153,156,157,159,160,161,163,168,169,170,171,172,173,174,175,176,177,178,179,180,183,187],taken:[4,75,87,88,94,112,126,151,158,161,181,183],talk:[1,143,148,168,170,177,182,184],talker:141,tangent:[4,175],tangenti:175,tar:175,target:[6,94,97,112,143,144,150,151,165,171,177,179,180,183,186],task:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,22,23,24,25,27,28,51,78,85,87,94,98,105,146,148,149,151,153,156,157,161,165,166,167,169,172,174,179,186,187,188],taskexecutor:27,taskresult:[27,152],tb3:[148,154],tb3_simulation_launch:[147,156,158,159,160,161,172,176,177,179,181,182,183,185],tbb:7,tcp:144,team:[14,144,179],tear:104,teardown:[28,165],teb:[3,94,149,153,163,165,172,187],teb_local_plann:150,teblocalplann:150,technic:[8,22,24,25,146,156,158,159,160,161,181],techniqu:[3,4,6,28,87,99,100,101,151,169,172],technolog:[8,14],tediou:171,teleop:[0,27,30,84,163],telepres:1,tell:[28,146,156,157,158,168,177],temperatur:94,templat:[101,142,146,151,157,161,167,171,177],tempor:[163,184],temporari:[22,23,24,25,181,183],tend:187,term:[94,146,161,169,170,181],termin:[88,100,128,129,130,141,147,150,156,166,168,169,175,177,178,179,180,182],terminatependinggo:161,test:[0,3,4,6,17,84,94,130,143,146,164,168,175,179,182,184,186],text:[156,158,184],tf1:171,tf2:[28,150,167,168,170,171,172],tf2_echo:[168,170],tf2_msg:168,tf2_ro:[159,166,168,170],tf2_tool:169,tf_:[159,160],tf_broadcast:83,tf_static:152,tfmessag:168,than:[17,20,22,24,25,28,55,56,61,65,79,83,87,90,92,94,96,97,98,106,107,129,130,143,150,151,152,153,154,159,161,163,170,172,176,177,178,179,181,182,185,187],thank:14,thei:[0,7,19,20,22,24,25,28,85,87,92,94,101,140,143,144,146,148,150,151,152,153,156,157,159,160,161,165,167,168,169,170,171,172,173,177,178,181,185,186],theinput:168,them:[4,7,22,27,28,89,94,105,109,110,114,130,143,144,146,148,149,151,152,153,154,156,157,158,159,160,166,169,170,171,172,173,174,177,178,180,181,182,185,186,187],themselv:[161,186],theoret:94,theori:94,therebi:146,therefor:[20,23,94,171,172,173,177,181,183,186],theta:[27,29,98,99,104,151,163,165,172,187],theta_scal:138,thetastarplann:[103,163],thi:[0,1,2,4,5,6,7,9,10,11,13,14,15,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,43,46,49,51,53,54,57,60,71,72,73,79,81,83,84,85,86,87,88,89,90,92,93,94,95,96,97,98,99,100,102,103,104,106,107,108,109,110,111,112,113,114,128,129,130,131,143,144,145,146,147,148,149,150,151,152,153,154,156,157,158,159,160,161,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],thing:[13,28,144,152,153,158,159,160,168,171,172,177,178,183],think:[0,8,28,172],third:[74,159,181,183],those:[9,14,28,99,143,152,165,169,171,172,173,174,177],though:[20,22,94,172,173,181,185],thought:[28,152,157],thread:[7,11,13,27,28,177],three:[26,28,101,153,170,172,173],threshhold:93,threshold:[61,87,89,93,94,97,98,106,135,152,163,180,181,183,187],threshold_to_consid:[94,154],throttl:[80,150,163],through:[1,9,17,18,19,20,23,24,25,27,28,29,41,92,94,103,110,114,129,130,143,146,147,148,150,151,152,153,154,158,163,165,167,168,169,170,171,172,173,177,178,181,182,183,184,187],throughout:[2,60,143,149,152,171,173],thrown:152,thu:[87,88,94,103,104,165,168,169,178],thusli:[166,172,187],tick:[19,20,22,23,24,25,28,60,74,77,80,81,82,152,157,163],ticket2:[10,11,13],ticket:[1,4,7,9,10,11,13,14,28,141,146,150,151,152,172,177,186],tie:4,tied:[28,130],tight:[98,130,165,172,187],tighter:172,till:74,tilt:175,time:[0,1,3,4,6,7,8,9,11,14,17,19,20,21,22,23,24,25,26,27,28,30,31,44,52,54,56,57,69,74,75,83,84,85,87,94,97,98,99,100,101,104,106,109,111,112,119,120,121,123,125,126,127,128,129,130,139,142,143,144,146,149,150,152,154,157,158,161,163,164,165,166,168,170,172,173,174,176,177,178,179,180,181,183,184,185,186,187],time_allow:[26,27,30,31,44,54,84,152],time_before_collis:87,time_granular:120,time_step:94,timedbehavior:156,timeexpir:86,timeexpiredcondit:150,timelin:146,timeout:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,54,57,72,73,85,87,89,92,93,104,125,150,156,157,185],timer:[68,163,169],timestamp:[27,126,168],timestep:94,timezon:146,tini:99,tip:[167,172,181],tireless:14,titl:148,tmp:[126,143,175],to_entri:143,to_numb:156,togeth:[20,28,168,170],toggle_filt:153,token:156,tol:163,toler:[19,28,56,61,84,85,88,90,94,95,97,98,100,102,113,115,122,124,128,129,130,139,151,152,154,160,163,174,180,187],tom:15,ton:177,too:[19,94,103,129,130,151,152,154,172,174],took:103,tool:[2,4,15,28,141,142,143,144,146,148,150,151,161,167,169,170,171,177,178,181],toolbar:179,toolbox:[28,149,169,172,177,182],top:[5,7,11,17,19,90,156,158,159,160,161,170,174,175,176,178,181,183,186],topic:[0,20,21,22,24,25,28,43,46,49,53,64,65,78,83,84,85,87,89,90,93,102,104,106,109,110,111,112,113,114,115,125,126,129,146,149,150,151,152,153,161,163,166,167,168,169,170,171,173,174,175,178,179,180,181,182,183,184,185],topic_nam:[43,46,49,53,93,181,183],torqu:104,total:[28,31,94,128,129,130,176],total_number_of_loop:160,touch:134,toward:[21,67,87,88,94,98,129,130,152,154,160,163,172,175,180,187],trace:177,track:[6,27,28,90,94,97,98,146,148,152,153,159,161,163,172,174,177,187],track_unknown_spac:[90,169,184],tracker:[0,94],trackingrout:27,tractabl:150,trade:[94,187],tradeoff:128,traffic:[149,163],trait:[154,172],trajectori:[3,4,10,87,104,115,118,120,131,132,133,134,136,137,138,151,153,160,165,166,172],trajectory_generator_nam:115,trajectory_point_step:94,trajectory_step:94,trajectoryvisu:94,tranform:169,trans_stopped_veloc:[91,124,139],transfer:5,transform:[5,15,28,70,83,84,85,87,90,94,97,102,106,109,112,115,141,147,148,150,151,152,159,163,166,167,168,169,171,172,181,182],transform_timeout:[84,99,100,102,156,174],transform_toler:[56,59,61,83,84,85,87,90,91,94,97,102,106,109,112,113,115,159,161,184,185],transform_tolerance_:159,transformavail:86,transformglobalplan:159,transit:[28,92,99,150,152,161,172,173,174,178,187],translat:[31,44,83,97,117,121,151,153,163,168,170,172],transpar:146,transport:143,transvers:170,travel:[20,28,44,59,77,94,128,129,130,152,163,168,169],travers:[26,28,94,128,129,130,152,170],treat:[90,184],tree:[1,2,11,17,21,22,23,24,25,26,29,30,31,47,48,54,57,59,61,74,75,76,77,78,79,80,81,82,141,147,148,149,152,158,161,162,165,169,170,171,173,174,188],treenod:186,treenodesmodel:186,trend:[129,130],tri:[28,150,159],triangl:87,triangular:111,trick:[167,177],trig:152,trigger:[11,19,20,22,24,25,28,50,77,79,81,87,94,97,98,106,143,150,151,152,153,163,173,174,185,187],trim:56,trinari:[181,183],trinary_costmap:90,trivial:[7,28,146,153,156,185,186],troubleshoot:142,truli:[11,172],truncat:[21,55,56,88,163],truncated_path:[21,55,179],truncatepath:[21,86,150,179],truncatepathloc:[86,88],trust:[11,144,148],trytoresolvesmoothererrorcod:174,tsc:146,tudela:163,tunabl:29,tune:[1,9,26,93,94,98,103,152,167,181,183,185,187],tunnel:144,turn:[26,88,94,97,104,106,129,130,143,151,152,153,154,163,165,171,172,174,176,177,187],turtl:93,turtlebot3:[142,147,156,157,158,159,160,161,174,176,180,181,182,183],turtlebot3_bringup:[180,182],turtlebot3_gazebo:147,turtlebot3_model:[147,180,182],turtlebot3_world:[93,147,181,183],turtlebot:[147,188],tutori:[3,8,15,17,19,85,86,87,151,153,163,164,165,166,167,168,169,170,171,172,173,177,178,185,186,187],tutorials_w:[181,183],tweak:143,twilio:156,twirling_cost_pow:94,twirling_cost_weight:94,twirlingcrit:[91,94],twist:[0,30,104,159,168],twiststamp:[0,159],twistwithcovari:168,twistwithcovariancestamp:168,two:[3,19,20,28,75,87,88,95,101,103,128,143,151,152,153,156,159,160,161,165,168,169,170,171,173,176,178,183,184,185],two_d_mod:168,txt:[156,158,159,160,161,168,169,171,175,177,178],type:[8,18,27,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,69,70,71,72,73,75,77,78,79,80,82,83,84,85,87,88,89,90,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,143,144,147,148,150,151,152,156,157,158,159,160,161,163,165,168,169,171,172,173,174,176,177,179,181,183,184,185,186,187],typenam:[152,161],typic:[9,19,20,28,87,129,130,146,152,159,166,168,170,172,176,181,182,183,187],ubuntu:184,udrf:2,uint16:[30,31,41,42,44,45,47,48,52,54,173],uint8:27,ukf_localization_nod:168,ukf_nod:168,ultim:23,unabl:[0,128,152],unaccept:[87,176],unaffect:143,unchang:143,unclear:28,uncom:[88,142,143],unconfigur:[28,173],under:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,21,85,110,114,143,144,146,150,151,152,153,156,157,163,165,166,168,169,171,174,177,184],underlai:[142,143],underli:[28,184],understand:[11,22,24,25,28,103,146,161,176,177,178,181,184],understood:181,undesir:181,unfair:8,unfamiliar:[11,28],unfold:183,unifi:171,unintend:143,uniqu:[22,24,25,28,143,148,150,151,154,156,157,161],unique_tb3_simulation_launch:154,unit:[28,85,92,146,164,170],univers:[5,170],unix:177,unknown:[28,71,72,73,90,95,103,108,114,128,129,130,153,173,181],unknown_cost_valu:90,unknown_threshold:[90,114,184],unless:[19,20,92,97,130,146],unlesscondit:[168,171],unlik:[19,156,176],unmodifi:143,unnecessari:[94,176],unord:153,unpredict:183,unreach:[128,129,130],unrespons:173,unsaf:[129,130,152],unscent:168,unsign:[58,71,72,73,158],unsmooth:174,unsmoothed_path:[52,174],unspecifi:[87,168],unsuit:146,unsynchron:175,untick:20,until:[19,20,21,27,28,74,87,98,115,129,130,141,143,151,159,161,163,168,177,179,184],untouch:[150,159],unus:94,unwant:[152,183],unzip:175,updat:[6,7,11,12,17,19,20,21,28,60,68,78,83,90,101,109,113,143,146,149,152,153,156,157,158,159,161,163,168,170,172,176,179,182,183,186],update_footprint_en:184,update_frequ:[90,169],update_min_a:83,update_min_d:83,update_r:[168,169],updatebound:158,updatecontentcommand:143,updatecost:158,updated_go:[21,78,179],updatego:150,updater:169,updatewithaddit:158,updatewithmax:158,updatewithoverwrit:158,updatewithtrueoverwrit:158,upgrad:[143,150],upon:[0,3,19,20,75,146,152,160,171],upper:97,upsampl:88,urdf:[2,28,147,166,167,170,172,182],urdf_config:171,usag:[11,27,106,143,170,171,173],usb:143,use:[0,1,3,4,8,9,10,11,13,17,20,21,22,23,24,25,27,28,41,42,45,52,65,78,83,84,85,87,88,89,90,94,95,96,97,98,99,100,102,104,109,110,114,115,129,130,131,141,143,145,146,147,148,149,150,151,152,153,154,156,157,158,159,160,161,165,166,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],use_approach_linear_velocity_sc:152,use_astar:[95,151,160],use_collision_detect:97,use_composit:[152,172,177,178],use_cost_regulated_linear_velocity_sc:97,use_final_approach_orient:[95,103,128],use_fixed_curvature_lookahead:[97,153],use_interpol:97,use_maximum:90,use_namespac:172,use_path_orient:[94,154],use_rclcpp_nod:152,use_regulated_linear_velocity_sc:97,use_respawn:[152,172,185],use_robot_state_pub:172,use_rotate_to_head:97,use_rviz:172,use_sim:180,use_sim_tim:[85,88,89,90,91,97,98,103,128,129,130,156,157,158,160,161,166,168,169,172,177,178,180,181,183,184,185,187],use_simul:172,use_start:[27,151],use_velocity_scaled_lookahead_dist:97,used:[0,1,5,13,14,15,17,18,19,20,22,23,24,25,26,27,28,30,31,41,42,43,46,49,51,52,53,54,56,57,65,76,77,80,82,83,87,88,90,93,94,101,105,110,112,114,129,130,142,143,144,148,149,150,151,152,153,154,156,157,158,159,160,161,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,181,183,185,186],useful:[0,20,21,22,24,25,28,78,83,87,94,99,143,144,151,152,154,157,166,168,169,170,171,172,173,178,179,181,183,184,186],useless:19,user:[1,2,3,7,9,14,18,22,23,24,25,27,28,29,75,79,83,87,100,105,111,125,143,144,146,150,151,152,153,161,163,167,169,172,173,177,178,182,184,187],userenvprob:143,uses:[5,6,17,20,28,47,48,83,87,88,90,94,95,99,101,110,114,141,148,149,150,153,154,156,157,163,165,168,169,170,171,172,175,180,184],using:[4,5,6,7,8,9,10,13,14,16,18,19,21,22,24,25,26,27,28,32,33,34,35,36,37,41,42,45,50,83,85,86,87,88,93,94,97,99,100,101,103,105,109,126,129,130,141,142,143,144,147,148,150,151,152,153,156,157,158,159,160,161,163,165,166,170,172,173,174,175,177,178,179,180,182,183,184,185,186,187],usr:[177,184],usual:[20,28,43,46,49,101,143,151,158,168,170,173,177,178,181],util:[22,23,24,25,28,94,143,148,151,152,153,154,157,165,166,168,171,178,181,183,184],valgrind:[177,178],valid:[28,66,83,87,88,106,109,110,112,114,129,130,148,153,161,163,169,172],valu:[43,46,49,53,65,83,85,87,88,89,90,93,94,97,100,103,106,110,111,112,114,128,129,130,143,146,151,152,153,156,157,158,159,160,161,163,166,168,169,170,171,172,174,176,177,180,181,183,185,186,187],valuabl:[7,11,146],vargovcik:163,vari:[94,97],variabl:[13,18,41,42,45,47,48,52,61,79,83,85,111,141,142,143,147,156,157,159,160,169,174,181,183,184,186],variant:[3,6,28,94,97,151,163,165],variat:[97,151,161,163,165,168],varient:151,varieti:[28,156],variou:[5,28,84,94,102,142,143,152,153,163,164,168,170,171],vast:[152,156],vcs:142,vcstool:142,vector:[22,28,41,47,51,84,85,87,89,90,92,94,95,96,99,102,103,104,109,110,111,114,115,128,152,153,158,160,161,166,177,181,183,184],vectorcrash:177,vehicl:[1,4,94,101,129,130,151,163,165],veloc:[1,4,9,13,29,82,84,87,89,94,97,98,112,116,117,124,135,138,139,148,151,156,159,163,164,165,168,172,185,187],velocity_smooth:104,velocity_timeout:104,velocitysmooth:153,vendor:169,verb:143,verbos:[168,169,172],veri:[6,7,11,14,16,18,22,24,28,94,99,129,146,152,164,166,170,171,172,187],verifi:[4,28,134,144,168,169,171],version:[24,25,28,88,115,141,142,144,147,151,159,169,171],vertex:[87,175],vertic:[107,185],vertical_fov_angl:184,via:[13,20,21,22,24,25,28,43,46,49,63,83,87,101,142,143,144,146,148,152,153,156,161,163,170,172,173,174,178,182,184,186],viabl:161,viapoint:[51,163],vicin:168,video:[23,143,158,179,180,184,186],view:[87,147,152,171,175,184,185,186],view_fram:169,vigil:144,vio:[28,168,170],violat:20,virtual:[21,87,94,152,156,157,158,159,160,161,168,171],visibl:[156,157,159,160,161,171],vision:[28,88,169],vision_msg:169,visit:[1,28,129,130,146],visual:[2,85,86,87,143,144,148,152,168,172,174,178,182,183,184,185],visualis:153,visualization_mark:169,viz_expans:154,vocabulari:20,volatil:171,voltag:65,volum:143,volumet:184,volumetr:163,vornoi:3,voxel:[7,90,153,163,169,176,184],voxel_decai:184,voxel_grid:[169,184],voxel_lay:[90,107,109,151,158,166,169,176,181],voxel_marked_cloud:151,voxel_min_point:184,voxel_s:184,voxel_unknown_cloud:151,voxellay:[90,169],vpitch:168,vroll:168,vscode:143,vslam:148,vslamcomparison2021:148,vtheta_sampl:[91,116],vx_max:94,vx_min:94,vx_sampl:[91,116],vx_std:94,vy_max:94,vy_sampl:[91,116],vy_std:94,vyaw:168,w_cost:88,w_cost_cusp_multipli:88,w_curv:88,w_data:[100,128,129,130],w_dist:88,w_euc_cost:103,w_heuristic_cost:103,w_smooth:[88,100,128,129,130],w_traversal_cost:103,waffl:[147,180,182],wai:[2,9,19,22,24,25,28,79,85,92,94,105,107,129,130,140,142,148,151,152,153,154,166,170,172,173,174,177,182,184,187],wait:[13,19,20,22,23,24,25,27,28,37,83,84,85,86,105,125,127,144,147,149,152,156,157,163,169,173],wait_act:157,wait_at_waypoint:[105,151],wait_dur:[19,22,23,24,25,57,86,157],wait_serv:57,waitact:157,waitatwaypoint:[105,151,163],waituntilnav2act:[27,152],walk:[19,20,28,143],walkthrough:18,wall:172,wallac:[14,163],want:[22,24,25,27,28,94,143,151,156,157,158,159,160,161,168,170,171,172,173,174,177,178,180,182,186],warehous:[27,28,166,172,181],warn:[96,111,129,150],was_complet:52,watch:147,watchdog:[9,92,135,148,150],water:20,wavefront:[95,152],waypoint:[17,27,29,125,126,127,148,149,151,152,173],waypoint_follow:[92,105,151,173],waypoint_imag:126,waypoint_pause_dur:[105,127,151],waypoint_task_executor:[125,126,127],waypoint_task_executor_plugin:[105,151],waypoint_task_executor_plugin_id:[125,126,127],waypointfollow:152,waypointtaskexecutor:151,weak:159,weakptr:[159,161],wear:104,web:[8,144],websit:[15,19],weigh:[131,132,133,134,135,136,137,138,139,140],weight1:88,weight2:88,weight:[28,56,83,88,94,100,103,128,129,130,138,150,152,154,172,181],welcom:146,well:[0,1,4,6,14,19,20,22,24,25,27,89,93,94,132,136,137,143,150,151,152,154,165,169,170,172,174,175,176,177,181,183,184,186],went:172,were:[11,14,19,28,84,149,150,151,152,153,154,170,171,172,173,181,183,185],what:[2,6,20,28,115,145,146,152,164,168,169,170,171,173,174,180],whatev:158,wheel:[28,168,170,171],wheel_diamet:168,wheel_radiu:[168,171],wheel_separ:168,wheel_width:171,wheel_xoff:171,wheel_ygap:[168,171],wheel_zoff:171,when:[11,19,20,21,22,24,28,56,59,63,65,69,77,79,80,82,83,84,87,89,90,92,94,96,97,98,103,104,105,106,109,112,126,129,130,135,139,141,143,144,146,150,151,152,154,156,157,158,159,160,161,163,165,166,168,169,170,171,172,173,175,176,177,178,179,181,183,185,186,187],whenev:[143,144,152,180,182],where:[1,6,10,13,20,23,27,28,87,94,100,106,112,114,126,130,131,142,143,146,147,150,151,152,154,157,158,159,160,161,163,166,168,169,170,171,172,173,178,180,181,183,185],wherea:[9,94,153,172,173],wherein:[165,166],whether:[52,83,87,88,90,92,94,95,97,99,100,103,104,105,106,107,108,109,110,111,112,113,114,115,118,120,121,122,123,124,125,126,127,128,129,130,131,134,146,149,151,156,158,159,163,168,169,171,172],which:[3,9,19,20,23,25,27,28,29,30,31,41,42,44,45,47,48,54,55,56,57,77,78,80,82,83,85,87,88,92,93,94,97,101,104,105,106,107,109,111,112,143,149,151,152,153,154,156,157,158,159,160,161,165,166,167,168,169,170,171,172,173,174,175,176,179,180,181,182,183,185,186],whilst:171,whip:[172,187],white:[14,143,148,176,181],whiter:181,whitespac:171,who:[94,146,161,172,179],whole:[19,56,146,158,169,175,183,185],whose:[88,169],why:[145,177],wide:[4,19,28,156,172],wider:172,widest:143,widget:171,width:[27,90,94,97,158,169,172],wiki:171,wilcox:[14,163],wild:14,willing:172,window:[129,130,152,158,165,166,168,169,170,171,172,175,176,177,178,186],wisdom:172,wise:[28,94,161,172],wish:[0,23,58,87,109,151,152,173,174],within:[10,19,20,22,28,58,83,87,94,98,128,129,130,143,144,146,152,153,158,161,163,168,169,171,172,173,178,184,186,187],withing:152,without:[1,4,14,17,28,56,87,88,89,94,99,107,109,143,144,150,151,152,154,158,161,166,167,169,172,177,179,181,182,187],wizard:14,wobbl:[94,129],won:[38,94,151,156,157,159,160,161,166,171,176,181],word:[144,153,159,160,170,176,181],work:[0,1,4,5,6,7,8,9,11,12,13,14,15,16,28,86,94,97,143,146,147,148,152,153,156,157,158,159,160,161,165,166,168,169,170,171,172,174,177,178,181,183,184,185],workflow:[28,143,144],workspac:[141,142,143,144,158,171,175,177,178,179,182,184,186],world:[8,9,27,28,143,147,148,156,168,169,170,172,176,179,181,182,183,184],world_fram:168,world_path:169,worldtomapvalid:27,worldwid:148,worri:[22,24,25,28,144,172,177],worst:12,worth:[22,24,94,172,176],would:[0,1,6,8,14,20,23,28,87,93,97,103,128,129,130,143,144,146,148,151,152,156,157,159,160,161,163,168,170,171,172,174,177,178,181,182,183,184,187],wouldacontrollerrecoveryhelp:[86,153],wouldaplannerrecoveryhelp:[86,153],wouldasmootherrecoveryhelp:[86,153,174],wouldn:[9,172],wrap:[19,27,28],wrapper:[17,28,156,157,177],write:[150,153,154,162,163,165,168,172,173,186],written:[6,28,156,158,159,160,161,169,176,181,183,185,186],wz_max:94,wz_std:94,x11:[143,144],x86_64:[177,184],x_increment:160,x_only_threshold:135,x_pose:172,x_reflect:171,xacro:[168,171],xml:[1,2,17,18,19,28,29,47,48,85,148,150,152,154,156,157,158,159,160,161,168,171,173,179,186],xml_tag_nam:157,xmln:171,xterm:[177,178],xvf:175,xxx:178,xy_goal_toler:[89,91,97,98,122,139,151,187],xytheta:91,xyz:[168,169,171],y_increment:160,y_pose:172,y_reflect:171,yaml:[27,87,93,151,152,154,156,157,158,159,160,161,165,166,168,172,173,174,175,176,177,178,180,181,183,184,185,187],yaml_filenam:[93,153,181,183],yaw:[83,168,172,181,183],yaw_goal_toler:[89,91,97,98,122,151,187],year:[6,14,148],yes:177,yet:[6,20,27,94,143,152,170,172],yolact:4,yolo3d:4,you:[0,4,5,6,10,11,12,13,14,18,21,27,28,58,83,85,88,89,93,94,97,101,103,109,130,131,141,142,143,144,146,147,148,151,152,153,154,156,157,158,159,160,161,163,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],your:[3,4,5,6,8,9,10,11,12,13,14,18,19,27,28,87,92,93,94,97,98,101,103,104,130,141,142,143,144,146,147,148,150,151,152,153,154,156,158,159,160,161,163,165,166,167,169,170,171,172,173,175,177,178,179,181,182,183,184,185,186,187],your_map:180,your_params_fil:[156,159,160,161],yourself:[146,152,174],yuk:13,z_hit:83,z_max:83,z_pose:172,z_rand:83,z_resolut:[90,114,169],z_short:83,z_voxel:[90,114,169],zero:[87,104,111,112,127,152,157,175,181,183],zmq:152,zone:[9,28,87,88,93,109,129,130,151,152,163,169,183,185,188],zurich:5},titles:["Projects for 2021 Summer Student Program","3. Assisted Teleop","1. Create a Configuration Assistant (Analog to MoveIt)","2. Create New Planner and Controller Plugins","1. Navigation Dynamic Obstacle Integration","3. Port Grid Maps to ROS 2 and Environmental Model","6. 2D/3D Localization Improvements","4. Navigation MultiThreading","5. Navigation Branding and Website","5. Navigation Safety Node","6. Semantic Integration","7. Reduce ROS 2 Nodes and Determinism","2. Advanced Navigation Testing Framework","8. Convert Twist to TwistStamped in Ecosystem and Run-Time Configuration","About and Contact","Related Projects","Robots Using","ROS to ROS 2 Navigation","Nav2 Behavior Trees","Detailed Behavior Tree Walkthrough","Introduction To Nav2 Specific Nodes","Follow Dynamic Point","Navigate Through Poses","Navigate To Pose and Pause Near Goal-Obstacle","Navigate To Pose","Navigate To Pose With Consistent Replanning And If Path Becomes Invalid","Odometry Calibration","Simple Commander API","Navigation Concepts","Configuration Guide","AssistedTeleop","BackUp","CancelAssistedTeleop","CancelBackUp","CancelControl","CancelDriveOnHeading","CancelSpin","CancelWait","ClearCostmapAroundRobot","ClearCostmapExceptRegion","ClearEntireCostmap","ComputePathThroughPoses","ComputePathToPose","ControllerSelector","DriveOnHeading","FollowPath","GoalCheckerSelector","NavigateThroughPoses","NavigateToPose","PlannerSelector","ReinitializeGlobalLocalization","RemovePassedGoals","SmoothPath","SmootherSelector","Spin","TruncatePath","TruncatePathLocal","Wait","AreErrorCodesPresent","DistanceTraveled","GloballyUpdatedGoal","GoalReached","GoalUpdated","InitialPoseReceived","IsBatteryCharging","IsBatteryLow","IsPathValid","IsStuck","PathExpiringTimer","TimeExpired","TransformAvailable","WouldAControllerRecoveryHelp","WouldAPlannerRecoveryHelp","WouldASmootherRecoveryHelp","PipelineSequence","RecoveryNode","RoundRobin","DistanceController","GoalUpdater","PathLongerOnApproach","RateController","SingleTrigger","SpeedController","AMCL","Behavior Server","Behavior-Tree Navigator","Behavior Tree XML Nodes","Collision Monitor","Constrained smoother","Controller Server","Costmap 2D","DWB Controller","Lifecycle Manager","Map Server / Saver","Model Predictive Path Integral Controller","NavFn Planner","Planner Server","Regulated Pure Pursuit","Rotation Shim Controller","Savitzky-Golay Smoother","Simple Smoother","Smac Planner","Smoother Server","Theta Star Planner","Velocity Smoother","Waypoint Follower","Binary Filter Parameters","Denoise Layer Parameters","Inflation Layer Parameters","Keepout Filter Parameters","Obstacle Layer Parameters","Range Sensor Parameters","Speed Filter Parameters","Static Layer Parameters","Voxel Layer Parameters","DWB Controller","XYTheta Iterator","Kinematic Parameters","Publisher","LimitedAccelGenerator","StandardTrajectoryGenerator","PoseProgressChecker","SimpleGoalChecker","SimpleProgressChecker","StoppedGoalChecker","InputAtWaypoint","PhotoAtWaypoint","WaitAtWaypoint","Smac 2D Planner","Smac Hybrid-A* Planner","Smac State Lattice Planner","BaseObstacleCritic","GoalAlignCritic","GoalDistCritic","ObstacleFootprintCritic","OscillationCritic","PathAlignCritic","PathDistCritic","PreferForwardCritic","RotateToGoalCritic","TwirlingCritic","Build Troubleshooting Guide","Build and Install","Dev Container Guide","Dev Containers","Development Guides","Getting Involved","Getting Started","Nav2","Dashing to Eloquent","Eloquent to Foxy","Foxy to Galactic","Galactic to Humble","Humble to Iron","Iron to Jazzy","Migration Guides","Writing a New Behavior Plugin","Writing a New Behavior Tree Plugin","Writing a New Costmap2D Plugin","Writing a New Controller Plugin","Writing a New Planner Plugin","Writing a New Navigator Plugin","Plugin Tutorials","Navigation Plugins","Roadmaps","Setting Up Navigation Plugins","Setting Up the Robot\u2019s Footprint","First-Time Robot Setup Guide","Setting Up Odometry","Setting Up Sensors","Setting Up Transformations","Setting Up The URDF","Tuning Guide","Adding a New Nav2 Task Server","Adding a Smoother to a BT","Camera Calibration","Filtering of Noise-Induced Obstacles","Get Backtrace in ROS 2 / Nav2","Profiling in ROS 2 / Nav2","Dynamic Object Following","Navigating with a Physical Turtlebot 3","Navigating with Keepout Zones","(SLAM) Navigating While Mapping","Navigating with Speed Limits","(STVL) Using an External Costmap Plugin","Using Collision Monitor","Groot - Interacting with Behavior Trees","Using Rotation Shim Controller","General Tutorials"],titleterms:{"2021":0,"case":152,"default":[84,89,90,96,105,151,153],"export":[156,157,158,159,160,161],"long":153,"new":[3,149,150,151,152,153,154,156,157,158,159,160,161,173],"static":[113,170],"while":182,Added:[151,152,153],Adding:[168,169,171,173,174,186],And:25,For:154,Near:23,ROS:[5,11,17,28,90,153,177,178],The:[154,171],Use:152,Uses:153,Using:[16,143,184,185,187],With:[19,25],about:14,academ:28,access:[153,154],ackermann:94,action:[20,28,86,150,151,152,154],add:157,advanc:12,algorithm:165,align:94,allow:[153,154],amcl:[83,152],analog:2,angl:[94,154],api:[27,152,153],appli:153,approach:152,architectur:149,areerrorcodespres:58,assist:[1,2,152],assistedteleop:[30,84],attribut:151,automat:177,backtrac:177,backup:[31,84,151],baseobstaclecrit:131,becom:25,behavior:[18,19,28,84,85,86,150,151,152,153,154,156,157,163,172,179,186],being:152,benchmark:153,binari:[106,142],bond:28,both:153,brand:8,bringup:[154,177,178],btservicenod:152,build:[141,142,143,166,168,169,171],cach:172,calibr:[26,175],camera:175,cancel:152,cancelassistedteleop:32,cancelbackup:33,cancelcontrol:34,canceldriveonhead:35,cancelspin:36,cancelwait:37,capabl:150,certif:146,chang:[149,151,152,153,154],check:153,checker:[27,151,152,153,163],citat:148,cleararea:152,clearcostmaparoundrobot:[38,151],clearcostmapexceptregion:[39,151],clearentirecostmap:40,click:179,code:[153,154,173],collis:[27,87,153,185],command:[27,152,153],common:[141,169],composit:[152,173],computepaththroughpos:[41,151],computepathtopos:[42,151],concept:28,conclus:[165,166,168,169,170,171,173],condit:[20,86],config:157,configur:[2,13,29,151,165,166,168,169,181,183,185,187],consist:25,constant:152,constrain:[88,152],constraint:94,constructor:153,contact:14,contain:[142,143,144],control:[3,20,28,86,89,91,94,98,115,151,152,153,159,163,165,172,187],controllerselector:43,controllerserv:151,convert:13,corner:152,costmap2d:[90,151,158,184],costmap:[27,28,90,93,94,150,151,153,163,169,181,183,184],costmap_2d_nod:153,costmaplay:152,crash:177,creat:[2,3,143,156,157,159,160,161,179],critic:[91,94,154],current_:151,curv:153,custom:[157,186],dash:149,dco:146,debug:154,deceler:153,decor:[20,86],demo:[27,168,170,185,187],denois:[107,153,176],depend:141,descript:[101,169],detail:19,detect:152,determin:11,dev:[143,144],develop:[142,145,146],direction:154,distanc:[152,153],distancecontrol:77,distancetravel:59,distribut:142,docker:142,doxygen:142,driveonhead:[44,84],drop:152,dwb:[91,115,153],dynam:[4,21,152,179],each:150,ecosystem:13,edit:186,eloqu:[149,150],enabl:[158,176,181,183],enumer:154,enviro:180,environ:171,environment:[5,28],error:[153,154,173],estim:28,euclidean:152,exampl:[27,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,102,103,104,105,106,107,109,112,128,129,130,147,148,165],except:152,execut:[185,187],executor:[152,163],expand:153,extend:152,extern:184,failur:[141,153],failure_toler:151,familiar:174,featur:87,feedback:[151,153],field:172,file:[153,154,156,159,160,161,168,169,177,178],filter:[28,90,93,106,109,112,150,151,153,163,176,181,183],first:167,fix:152,follow:[21,28,94,105,179],followpath:[45,151],followpoint:150,footprint:[27,166,172],form:28,forward:[94,153],foxi:[150,151],framework:12,from:[153,177,178],galact:[151,152],gazebo:[152,168,169],gener:[94,142,150,188],get:[144,146,147,177,182],give:153,global:28,globallyupdatedgo:60,goal:[23,94,151,152,153,154,163,180],goal_checker_id:151,goalaligncrit:132,goalcheckerselector:46,goaldistcrit:133,goalreach:61,goalupd:62,goalupdat:78,golai:[99,153],gradientlay:158,grid:5,groot:[151,152,186],guid:[29,141,143,145,155,167,172],handl:154,handler:94,help:142,heurist:172,horizon:94,how:[144,176],humbl:[152,153,164],hybrid:129,ignor:152,imag:[142,143,169],improv:[6,152],includ:[152,153],induc:176,inflat:[94,108,172],info:[93,181,183],inform:151,initi:180,initialposereceiv:63,input:[30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,70,71,72,73,75,77,78,79,80,82],inputatwaypoint:125,instal:[142,147,184],integr:[4,10,94,153],interact:186,interfac:[151,182],interpret:178,introduc:154,introduct:[20,166,168,169,170],invalid:[25,152],invert:152,involv:146,iron:[153,154,164],isbatterycharg:64,isbatterychargingcondit:153,isbatterylow:65,ispathvalid:66,isstuck:67,issu:141,iter:116,jazzi:[154,164],keepout:[109,181],kinemat:[117,152],larg:177,laserscan:169,lattic:130,launch:[151,152,153,154,168,169,171,172,177,178,180,182,184],layer:[28,94,107,108,110,113,114,150,153,154,163,176],librari:157,licens:146,lifecycl:[28,92,143,152,173],limit:[152,153,183],limitedaccelgener:119,live:152,load:153,local:[6,28,168,169],locat:180,logic:152,lookahead:153,loop:153,love:172,major:152,make:158,manag:[92,152],map:[5,93,150,153,169,182],map_serv:153,mark:151,mask:[181,183],messag:[150,169],migrat:155,model:[5,94,152,153],modifi:[174,184],monitor:[87,152,153,185],more:153,motion:[94,152],move:154,moveit:2,mppi:[94,154],multi:154,multipl:[152,153],multithread:7,name:[153,154,156,157,159,160,161],nav2:[18,20,28,141,148,151,152,153,169,172,173,176,177,178,179,180,181,183,185],nav2_cor:152,nav2_costmap_2d:169,navfn:[95,151,152],navig:[4,7,8,9,12,17,19,22,23,24,25,28,85,147,150,152,153,161,163,165,180,181,182,183],navigatethroughpos:[47,151],navigatetopos:[48,151],navigation2:[149,170,182,184],node:[9,11,20,28,86,151,152,153,163,169,173,174,177,178,186],nois:176,note:94,object:179,observ:87,obstacl:[4,23,94,110,151,154,172,176],obstaclefootprintcrit:134,odometri:[26,28,168],offer:172,offset:94,onli:152,option:[154,172],orient:152,origin:146,oscillationcrit:135,other:[28,172],ouput:[55,56],our:148,output:[31,41,42,43,44,45,46,47,48,49,51,52,53,54],overview:[19,27,28,148,156,157,158,159,160,161,174,175,176,177,178,179,180,181,182,183,184,185,186,187],packag:149,page:172,panel:[151,153],param:[152,154,156,159,160,161],paramet:[59,61,78,83,84,85,87,88,89,90,92,93,94,95,96,97,98,99,100,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,151,152,153,154,184],parameteriz:153,particl:150,pass:[156,159,160,161],path:[25,94,152,153,154],pathaligncrit:136,pathdistcrit:137,pathexpiringtim:68,pathlongeronapproach:[79,152],paus:23,photoatwaypoint:126,physic:[171,180],pipelinesequ:[20,74],place:172,planner:[3,28,95,96,101,103,128,129,130,151,152,153,154,157,160,163,165,172],plannerselector:49,plugin:[3,84,86,89,90,91,96,101,105,149,150,151,152,153,154,156,157,158,159,160,161,162,163,165,168,169,172,174,184],point:[21,179],pointcloud2:[151,169],pointcloud:151,polygon:87,port:[5,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,70,71,72,73,75,77,78,79,80,82],pose:[19,22,23,24,25,153,180],poseprogresscheck:[121,153],posit:28,potenti:172,predict:[94,153],prefer:94,preferforwardcrit:138,preliminari:[177,178],prepar:[181,183,185],prerequisit:[19,144,168],primari:187,process:[146,152],profil:178,program:0,progress:163,progress_checker_plugin:153,project:[0,15,177],properti:171,provid:[89,101,105],prune:153,publish:[118,153,170,171,181,183],pure:[97,159],pursuit:[97,159],python:[152,153],radiu:172,rai:151,rang:[111,169],rate:152,ratecontrol:80,rebuild:143,recoveri:[19,20,28,151,152],recoverynod:75,recurs:153,reduc:[11,152],refactor:152,refin:153,regul:[97,153],regulatedpurepursuitcontrol:151,reinitializegloballoc:50,relat:15,releas:142,remov:[151,152,153],removepassedgo:51,renam:153,replan:[19,25,152],report:141,represent:28,requir:[156,157,158,159,160,161,174,175,176,180,181,182,183,185],respawn:152,result:[152,154,178],revers:153,roadmap:164,robot:[16,152,154,166,167,168,171,172,182],roll:142,rotat:[98,152,172,187],rotatetogoalcrit:139,roundrobin:[20,76],rpp:[152,153],run:[13,147,153,156,157,158,159,160,161,166,168,169,176,179,181,183],rviz:[151,153,166,169,171,179,180,184],safeti:[9,153],save:153,saver:93,savitzki:[99,153],scale:152,secur:144,select:[150,165,172],semant:10,send:180,sensor:[111,169],sensor_msg:[151,169],server:[28,84,88,89,93,96,102,150,152,153,154,165,173,181,183],servic:152,set:[165,166,168,169,170,171],setup:[167,168,179,180,184],shim:[98,152,187],simpl:[27,100,152,153],simplegoalcheck:122,simpleprogresscheck:123,simplif:182,simul:[168,169,179],singletrigg:81,size:94,slam:[28,182],slam_toolbox:169,smac:[101,128,129,130,152,153,154,172],smacplann:151,smacplanner2d:152,smacplannerhybrid:153,small:152,smoother:[28,88,99,100,102,104,152,153,163,174],smootherselector:[53,153],smoothpath:52,sourc:[87,142],spawn:152,specif:20,specifi:174,speed:[112,153,183],speedcontrol:82,spin:[54,84],sponsor:148,stabl:153,stack:[176,181,183,185],standard:[28,151],standardtrajectorygener:120,star:103,start:[143,144,147,153,182],state:[28,130,153,171],step:[156,157,158,159,160,161,174,175,176,179,180,181,182,183,184],stoppedgoalcheck:124,straightlin:160,student:0,stvl:184,substitut:154,subtre:19,summari:165,summer:0,support:[151,152],system:168,task:[152,163,173],teleop:[1,152],termin:143,test:[12,153],theta:[103,152],thetastarplann:151,through:[22,156,159,160,161],time:[13,151,153,167],timeexpir:69,timeout:[152,153],toler:153,trace:151,trajectori:[91,94],transform:170,transformavail:70,tree:[18,19,28,85,86,150,151,153,157,163,179,186],troubleshoot:141,truncatepath:55,truncatepathloc:[56,152],tune:172,turtlebot:180,tutori:[156,157,158,159,160,161,162,174,175,176,179,180,181,182,183,184,188],twirl:94,twirlingcrit:140,twist:13,twiststamp:13,type:153,unit:151,updat:[150,151],urdf:[168,169,171],usag:151,use:144,use_final_approach_orient:152,use_sim_tim:153,user:94,using:[168,169,171],variabl:180,veloc:[104,152,153],verif:[166,168,169],visual:[94,166,169,171,186],viz_expans:153,voxel:[114,154],wait:57,waitatwaypoint:127,walkthrough:19,waypoint:[28,105,153,163],websit:8,what:[144,187],when:153,why:144,wisdom:94,word:94,work:[144,150,176,182],wouldacontrollerrecoveryhelp:71,wouldaplannerrecoveryhelp:72,wouldasmootherrecoveryhelp:73,write:[156,157,158,159,160,161,171],xml:[86,151,174],xytheta:116,yaml:153,your:[157,168,174,180],zone:181}}) \ No newline at end of file +Search.setIndex({docnames:["2021summerOfCode/Summer_2021_Student_Program","2021summerOfCode/projects/assisted_teleop","2021summerOfCode/projects/create_configuration_assistant","2021summerOfCode/projects/create_plugins","2021summerOfCode/projects/dynamic","2021summerOfCode/projects/grid_maps","2021summerOfCode/projects/localization","2021summerOfCode/projects/multithreading","2021summerOfCode/projects/navigation_rebranding","2021summerOfCode/projects/safety_node","2021summerOfCode/projects/semantics","2021summerOfCode/projects/spinners","2021summerOfCode/projects/testing","2021summerOfCode/projects/twist_n_config","about/index","about/related_projects","about/robots","about/ros1_comparison","behavior_trees/index","behavior_trees/overview/detailed_behavior_tree_walkthrough","behavior_trees/overview/nav2_specific_nodes","behavior_trees/trees/follow_point","behavior_trees/trees/nav_through_poses_recovery","behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle","behavior_trees/trees/nav_to_pose_recovery","behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid","behavior_trees/trees/odometry_calibration","commander_api/index","concepts/index","configuration/index","configuration/packages/bt-plugins/actions/AssistedTeleop","configuration/packages/bt-plugins/actions/BackUp","configuration/packages/bt-plugins/actions/CancelAssistedTeleop","configuration/packages/bt-plugins/actions/CancelBackUp","configuration/packages/bt-plugins/actions/CancelControl","configuration/packages/bt-plugins/actions/CancelDriveOnHeading","configuration/packages/bt-plugins/actions/CancelSpin","configuration/packages/bt-plugins/actions/CancelWait","configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot","configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion","configuration/packages/bt-plugins/actions/ClearEntireCostmap","configuration/packages/bt-plugins/actions/ComputePathThroughPoses","configuration/packages/bt-plugins/actions/ComputePathToPose","configuration/packages/bt-plugins/actions/ControllerSelector","configuration/packages/bt-plugins/actions/DriveOnHeading","configuration/packages/bt-plugins/actions/FollowPath","configuration/packages/bt-plugins/actions/GoalCheckerSelector","configuration/packages/bt-plugins/actions/NavigateThroughPoses","configuration/packages/bt-plugins/actions/NavigateToPose","configuration/packages/bt-plugins/actions/PlannerSelector","configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization","configuration/packages/bt-plugins/actions/RemovePassedGoals","configuration/packages/bt-plugins/actions/Smooth","configuration/packages/bt-plugins/actions/SmootherSelector","configuration/packages/bt-plugins/actions/Spin","configuration/packages/bt-plugins/actions/TruncatePath","configuration/packages/bt-plugins/actions/TruncatePathLocal","configuration/packages/bt-plugins/actions/Wait","configuration/packages/bt-plugins/conditions/AreErrorCodesPresent","configuration/packages/bt-plugins/conditions/DistanceTraveled","configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal","configuration/packages/bt-plugins/conditions/GoalReached","configuration/packages/bt-plugins/conditions/GoalUpdated","configuration/packages/bt-plugins/conditions/InitialPoseReceived","configuration/packages/bt-plugins/conditions/IsBatteryCharging","configuration/packages/bt-plugins/conditions/IsBatteryLow","configuration/packages/bt-plugins/conditions/IsPathValid","configuration/packages/bt-plugins/conditions/IsStuck","configuration/packages/bt-plugins/conditions/PathExpiringTimer","configuration/packages/bt-plugins/conditions/TimeExpired","configuration/packages/bt-plugins/conditions/TransformAvailable","configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp","configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp","configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp","configuration/packages/bt-plugins/controls/PipelineSequence","configuration/packages/bt-plugins/controls/RecoveryNode","configuration/packages/bt-plugins/controls/RoundRobin","configuration/packages/bt-plugins/decorators/DistanceController","configuration/packages/bt-plugins/decorators/GoalUpdater","configuration/packages/bt-plugins/decorators/PathLongerOnApproach","configuration/packages/bt-plugins/decorators/RateController","configuration/packages/bt-plugins/decorators/SingleTrigger","configuration/packages/bt-plugins/decorators/SpeedController","configuration/packages/collision_monitor/configuring-collision-detector-node","configuration/packages/collision_monitor/configuring-collision-monitor-node","configuration/packages/configuring-amcl","configuration/packages/configuring-behavior-server","configuration/packages/configuring-bt-navigator","configuration/packages/configuring-bt-xml","configuration/packages/configuring-collision-monitor","configuration/packages/configuring-constrained-smoother","configuration/packages/configuring-controller-server","configuration/packages/configuring-costmaps","configuration/packages/configuring-dwb-controller","configuration/packages/configuring-lifecycle","configuration/packages/configuring-map-server","configuration/packages/configuring-mppic","configuration/packages/configuring-navfn","configuration/packages/configuring-planner-server","configuration/packages/configuring-regulated-pp","configuration/packages/configuring-rotation-shim-controller","configuration/packages/configuring-savitzky-golay-smoother","configuration/packages/configuring-simple-smoother","configuration/packages/configuring-smac-planner","configuration/packages/configuring-smoother-server","configuration/packages/configuring-thetastar","configuration/packages/configuring-velocity-smoother","configuration/packages/configuring-waypoint-follower","configuration/packages/costmap-plugins/binary_filter","configuration/packages/costmap-plugins/denoise","configuration/packages/costmap-plugins/inflation","configuration/packages/costmap-plugins/keepout_filter","configuration/packages/costmap-plugins/obstacle","configuration/packages/costmap-plugins/range","configuration/packages/costmap-plugins/speed_filter","configuration/packages/costmap-plugins/static","configuration/packages/costmap-plugins/voxel","configuration/packages/dwb-params/controller","configuration/packages/dwb-params/iterator","configuration/packages/dwb-params/kinematic","configuration/packages/dwb-params/visualization","configuration/packages/dwb-plugins/limited_accel_generator","configuration/packages/dwb-plugins/standard_traj_generator","configuration/packages/nav2_controller-plugins/pose_progress_checker","configuration/packages/nav2_controller-plugins/simple_goal_checker","configuration/packages/nav2_controller-plugins/simple_progress_checker","configuration/packages/nav2_controller-plugins/stopped_goal_checker","configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint","configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint","configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint","configuration/packages/smac/configuring-smac-2d","configuration/packages/smac/configuring-smac-hybrid","configuration/packages/smac/configuring-smac-lattice","configuration/packages/trajectory_critics/base_obstacle","configuration/packages/trajectory_critics/goal_align","configuration/packages/trajectory_critics/goal_dist","configuration/packages/trajectory_critics/obstacle_footprint","configuration/packages/trajectory_critics/oscillation","configuration/packages/trajectory_critics/path_align","configuration/packages/trajectory_critics/path_dist","configuration/packages/trajectory_critics/prefer_forward","configuration/packages/trajectory_critics/rotate_to_goal","configuration/packages/trajectory_critics/twirling","development_guides/build_docs/build_troubleshooting_guide","development_guides/build_docs/index","development_guides/devcontainer_docs/devcontainer_guide","development_guides/devcontainer_docs/index","development_guides/index","development_guides/involvement_docs/index","getting_started/index","index","migration/Dashing","migration/Eloquent","migration/Foxy","migration/Galactic","migration/Humble","migration/Iron","migration/index","plugin_tutorials/docs/writing_new_behavior_plugin","plugin_tutorials/docs/writing_new_bt_plugin","plugin_tutorials/docs/writing_new_costmap2d_plugin","plugin_tutorials/docs/writing_new_nav2controller_plugin","plugin_tutorials/docs/writing_new_nav2planner_plugin","plugin_tutorials/docs/writing_new_navigator_plugin","plugin_tutorials/index","plugins/index","roadmap/roadmap","setup_guides/algorithm/select_algorithm","setup_guides/footprint/setup_footprint","setup_guides/index","setup_guides/odom/setup_odom","setup_guides/sensors/setup_sensors","setup_guides/transformation/setup_transforms","setup_guides/urdf/setup_urdf","tuning/index","tutorials/docs/adding_a_nav2_task_server","tutorials/docs/adding_smoother","tutorials/docs/camera_calibration","tutorials/docs/filtering_of_noise-induced_obstacles","tutorials/docs/get_backtrace","tutorials/docs/get_profile","tutorials/docs/navigation2_dynamic_point_following","tutorials/docs/navigation2_on_real_turtlebot3","tutorials/docs/navigation2_with_keepout_filter","tutorials/docs/navigation2_with_slam","tutorials/docs/navigation2_with_speed_filter","tutorials/docs/navigation2_with_stvl","tutorials/docs/using_collision_monitor","tutorials/docs/using_groot","tutorials/docs/using_shim_controller","tutorials/index"],envversion:{"sphinx.domains.c":2,"sphinx.domains.changeset":1,"sphinx.domains.citation":1,"sphinx.domains.cpp":3,"sphinx.domains.index":1,"sphinx.domains.javascript":2,"sphinx.domains.math":2,"sphinx.domains.python":2,"sphinx.domains.rst":2,"sphinx.domains.std":2,sphinx:56},filenames:["2021summerOfCode/Summer_2021_Student_Program.rst","2021summerOfCode/projects/assisted_teleop.rst","2021summerOfCode/projects/create_configuration_assistant.rst","2021summerOfCode/projects/create_plugins.rst","2021summerOfCode/projects/dynamic.rst","2021summerOfCode/projects/grid_maps.rst","2021summerOfCode/projects/localization.rst","2021summerOfCode/projects/multithreading.rst","2021summerOfCode/projects/navigation_rebranding.rst","2021summerOfCode/projects/safety_node.rst","2021summerOfCode/projects/semantics.rst","2021summerOfCode/projects/spinners.rst","2021summerOfCode/projects/testing.rst","2021summerOfCode/projects/twist_n_config.rst","about/index.rst","about/related_projects.rst","about/robots.rst","about/ros1_comparison.rst","behavior_trees/index.rst","behavior_trees/overview/detailed_behavior_tree_walkthrough.rst","behavior_trees/overview/nav2_specific_nodes.rst","behavior_trees/trees/follow_point.rst","behavior_trees/trees/nav_through_poses_recovery.rst","behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst","behavior_trees/trees/nav_to_pose_recovery.rst","behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst","behavior_trees/trees/odometry_calibration.rst","commander_api/index.rst","concepts/index.rst","configuration/index.rst","configuration/packages/bt-plugins/actions/AssistedTeleop.rst","configuration/packages/bt-plugins/actions/BackUp.rst","configuration/packages/bt-plugins/actions/CancelAssistedTeleop.rst","configuration/packages/bt-plugins/actions/CancelBackUp.rst","configuration/packages/bt-plugins/actions/CancelControl.rst","configuration/packages/bt-plugins/actions/CancelDriveOnHeading.rst","configuration/packages/bt-plugins/actions/CancelSpin.rst","configuration/packages/bt-plugins/actions/CancelWait.rst","configuration/packages/bt-plugins/actions/ClearCostmapAroundRobot.rst","configuration/packages/bt-plugins/actions/ClearCostmapExceptRegion.rst","configuration/packages/bt-plugins/actions/ClearEntireCostmap.rst","configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst","configuration/packages/bt-plugins/actions/ComputePathToPose.rst","configuration/packages/bt-plugins/actions/ControllerSelector.rst","configuration/packages/bt-plugins/actions/DriveOnHeading.rst","configuration/packages/bt-plugins/actions/FollowPath.rst","configuration/packages/bt-plugins/actions/GoalCheckerSelector.rst","configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst","configuration/packages/bt-plugins/actions/NavigateToPose.rst","configuration/packages/bt-plugins/actions/PlannerSelector.rst","configuration/packages/bt-plugins/actions/ReinitializeGlobalLocalization.rst","configuration/packages/bt-plugins/actions/RemovePassedGoals.rst","configuration/packages/bt-plugins/actions/Smooth.rst","configuration/packages/bt-plugins/actions/SmootherSelector.rst","configuration/packages/bt-plugins/actions/Spin.rst","configuration/packages/bt-plugins/actions/TruncatePath.rst","configuration/packages/bt-plugins/actions/TruncatePathLocal.rst","configuration/packages/bt-plugins/actions/Wait.rst","configuration/packages/bt-plugins/conditions/AreErrorCodesPresent.rst","configuration/packages/bt-plugins/conditions/DistanceTraveled.rst","configuration/packages/bt-plugins/conditions/GloballyUpdatedGoal.rst","configuration/packages/bt-plugins/conditions/GoalReached.rst","configuration/packages/bt-plugins/conditions/GoalUpdated.rst","configuration/packages/bt-plugins/conditions/InitialPoseReceived.rst","configuration/packages/bt-plugins/conditions/IsBatteryCharging.rst","configuration/packages/bt-plugins/conditions/IsBatteryLow.rst","configuration/packages/bt-plugins/conditions/IsPathValid.rst","configuration/packages/bt-plugins/conditions/IsStuck.rst","configuration/packages/bt-plugins/conditions/PathExpiringTimer.rst","configuration/packages/bt-plugins/conditions/TimeExpired.rst","configuration/packages/bt-plugins/conditions/TransformAvailable.rst","configuration/packages/bt-plugins/conditions/WouldAControllerRecoveryHelp.rst","configuration/packages/bt-plugins/conditions/WouldAPlannerRecoveryHelp.rst","configuration/packages/bt-plugins/conditions/WouldASmootherRecoveryHelp.rst","configuration/packages/bt-plugins/controls/PipelineSequence.rst","configuration/packages/bt-plugins/controls/RecoveryNode.rst","configuration/packages/bt-plugins/controls/RoundRobin.rst","configuration/packages/bt-plugins/decorators/DistanceController.rst","configuration/packages/bt-plugins/decorators/GoalUpdater.rst","configuration/packages/bt-plugins/decorators/PathLongerOnApproach.rst","configuration/packages/bt-plugins/decorators/RateController.rst","configuration/packages/bt-plugins/decorators/SingleTrigger.rst","configuration/packages/bt-plugins/decorators/SpeedController.rst","configuration/packages/collision_monitor/configuring-collision-detector-node.rst","configuration/packages/collision_monitor/configuring-collision-monitor-node.rst","configuration/packages/configuring-amcl.rst","configuration/packages/configuring-behavior-server.rst","configuration/packages/configuring-bt-navigator.rst","configuration/packages/configuring-bt-xml.rst","configuration/packages/configuring-collision-monitor.rst","configuration/packages/configuring-constrained-smoother.rst","configuration/packages/configuring-controller-server.rst","configuration/packages/configuring-costmaps.rst","configuration/packages/configuring-dwb-controller.rst","configuration/packages/configuring-lifecycle.rst","configuration/packages/configuring-map-server.rst","configuration/packages/configuring-mppic.rst","configuration/packages/configuring-navfn.rst","configuration/packages/configuring-planner-server.rst","configuration/packages/configuring-regulated-pp.rst","configuration/packages/configuring-rotation-shim-controller.rst","configuration/packages/configuring-savitzky-golay-smoother.rst","configuration/packages/configuring-simple-smoother.rst","configuration/packages/configuring-smac-planner.rst","configuration/packages/configuring-smoother-server.rst","configuration/packages/configuring-thetastar.rst","configuration/packages/configuring-velocity-smoother.rst","configuration/packages/configuring-waypoint-follower.rst","configuration/packages/costmap-plugins/binary_filter.rst","configuration/packages/costmap-plugins/denoise.rst","configuration/packages/costmap-plugins/inflation.rst","configuration/packages/costmap-plugins/keepout_filter.rst","configuration/packages/costmap-plugins/obstacle.rst","configuration/packages/costmap-plugins/range.rst","configuration/packages/costmap-plugins/speed_filter.rst","configuration/packages/costmap-plugins/static.rst","configuration/packages/costmap-plugins/voxel.rst","configuration/packages/dwb-params/controller.rst","configuration/packages/dwb-params/iterator.rst","configuration/packages/dwb-params/kinematic.rst","configuration/packages/dwb-params/visualization.rst","configuration/packages/dwb-plugins/limited_accel_generator.rst","configuration/packages/dwb-plugins/standard_traj_generator.rst","configuration/packages/nav2_controller-plugins/pose_progress_checker.rst","configuration/packages/nav2_controller-plugins/simple_goal_checker.rst","configuration/packages/nav2_controller-plugins/simple_progress_checker.rst","configuration/packages/nav2_controller-plugins/stopped_goal_checker.rst","configuration/packages/nav2_waypoint_follower-plugins/input_at_waypoint.rst","configuration/packages/nav2_waypoint_follower-plugins/photo_at_waypoint.rst","configuration/packages/nav2_waypoint_follower-plugins/wait_at_waypoint.rst","configuration/packages/smac/configuring-smac-2d.rst","configuration/packages/smac/configuring-smac-hybrid.rst","configuration/packages/smac/configuring-smac-lattice.rst","configuration/packages/trajectory_critics/base_obstacle.rst","configuration/packages/trajectory_critics/goal_align.rst","configuration/packages/trajectory_critics/goal_dist.rst","configuration/packages/trajectory_critics/obstacle_footprint.rst","configuration/packages/trajectory_critics/oscillation.rst","configuration/packages/trajectory_critics/path_align.rst","configuration/packages/trajectory_critics/path_dist.rst","configuration/packages/trajectory_critics/prefer_forward.rst","configuration/packages/trajectory_critics/rotate_to_goal.rst","configuration/packages/trajectory_critics/twirling.rst","development_guides/build_docs/build_troubleshooting_guide.rst","development_guides/build_docs/index.rst","development_guides/devcontainer_docs/devcontainer_guide.md","development_guides/devcontainer_docs/index.md","development_guides/index.rst","development_guides/involvement_docs/index.rst","getting_started/index.rst","index.rst","migration/Dashing.rst","migration/Eloquent.rst","migration/Foxy.rst","migration/Galactic.rst","migration/Humble.rst","migration/Iron.rst","migration/index.rst","plugin_tutorials/docs/writing_new_behavior_plugin.rst","plugin_tutorials/docs/writing_new_bt_plugin.rst","plugin_tutorials/docs/writing_new_costmap2d_plugin.rst","plugin_tutorials/docs/writing_new_nav2controller_plugin.rst","plugin_tutorials/docs/writing_new_nav2planner_plugin.rst","plugin_tutorials/docs/writing_new_navigator_plugin.rst","plugin_tutorials/index.rst","plugins/index.rst","roadmap/roadmap.rst","setup_guides/algorithm/select_algorithm.rst","setup_guides/footprint/setup_footprint.rst","setup_guides/index.rst","setup_guides/odom/setup_odom.rst","setup_guides/sensors/setup_sensors.rst","setup_guides/transformation/setup_transforms.rst","setup_guides/urdf/setup_urdf.rst","tuning/index.rst","tutorials/docs/adding_a_nav2_task_server.rst","tutorials/docs/adding_smoother.rst","tutorials/docs/camera_calibration.rst","tutorials/docs/filtering_of_noise-induced_obstacles.rst","tutorials/docs/get_backtrace.rst","tutorials/docs/get_profile.rst","tutorials/docs/navigation2_dynamic_point_following.rst","tutorials/docs/navigation2_on_real_turtlebot3.rst","tutorials/docs/navigation2_with_keepout_filter.rst","tutorials/docs/navigation2_with_slam.rst","tutorials/docs/navigation2_with_speed_filter.rst","tutorials/docs/navigation2_with_stvl.rst","tutorials/docs/using_collision_monitor.rst","tutorials/docs/using_groot.rst","tutorials/docs/using_shim_controller.rst","tutorials/index.rst"],objects:{},objnames:{},objtypes:{},terms:{"000":[170,172],"000000":171,"0000008":170,"0000075":170,"0001":91,"001":[85,91,93,99,100,170,171,189],"002":170,"003":170,"005":85,"015":[90,96,131,132,171],"015000":171,"022":171,"025":[19,22,24,27,31,44,88,93,122,173],"035":171,"047198":171,"048":186,"0508":171,"055":171,"05s":96,"092":170,"0_1602582820":128,"0x000055555555828b":179,"0x0000555555558e1d":179,"0x000055555555936c":179,"0x0000555555559cfc":179,"0x00007ffff79cc859":179,"0x00007ffff7c52951":179,"0x00007ffff7c553eb":179,"0x00007ffff7c5e47c":179,"0x00007ffff7c5e4e7":179,"0x00007ffff7c5e799":179,"0x5555555cfb40":179,"0x5555555cfdb0":179,"0x7fffffffc108":179,"100":[83,84,85,90,92,96,114,155,170,172,175,179,181,183,185,188],"1000":[96,102,130,131,132],"10000":[96,155,175],"1000000":[130,131,132],"10001":175,"10002":175,"1001":155,"10099":175,"100hz":19,"100m":[27,103,154],"101":[58,155,175,183],"103":[153,172],"105":[28,150,170,172],"107":58,"1070":179,"1091":179,"10cm":[130,131,172],"113m":103,"119":58,"120000":171,"124":160,"125":[130,171],"1263":153,"127":170,"128":173,"12th":170,"12thread":154,"130":171,"144m":103,"146m":103,"160":173,"164":173,"1660":152,"171":160,"1780":152,"1784":152,"180":[83,84],"185":90,"1855":153,"1859":152,"188":[183,185],"1882":153,"195":168,"196":185,"199":[155,175],"1ms":101,"1st":170,"200":[172,175],"2000":[85,96],"2000000":90,"2005":166,"200m":[103,154],"201":[155,175],"2020":150,"2021":[103,145,150,174,186],"2023":[99,150],"204":174,"20cm":172,"20hz":96,"20m":172,"20mm":177,"215":171,"2181":153,"2204":153,"2247":153,"2263":153,"2264":153,"2295":153,"2338":153,"2411":154,"243m":103,"2473":154,"2481":154,"2488":154,"254":171,"255":[92,160,183],"2567":155,"2569":154,"2591":154,"2592":154,"25hz":154,"2607":154,"2627":154,"2642":154,"2665":154,"2696":154,"2701":154,"2704":154,"2718":154,"2750":154,"2752":154,"2753":154,"2772":154,"2787":154,"280000":171,"2804":154,"2856":154,"2865":154,"2867":154,"2875":154,"2904":154,"2964":154,"2965":154,"2976":154,"2982":155,"299":[155,175],"2992":154,"2nd":170,"300":[174,175],"301":[155,175],"30hz":96,"3131":155,"3146":155,"3159":155,"3165":155,"3168":155,"3174":155,"3201":155,"3204":155,"3218":155,"3219":155,"3222":155,"3227":155,"3228":155,"3229":155,"3248":155,"325":[134,138],"3251":155,"3255":155,"3283":155,"32gb":154,"3320":155,"3324":155,"333":22,"3345":155,"3374":155,"3414":155,"3504":155,"3512":155,"3513":155,"3519":155,"3530":155,"3553":155,"3555":155,"3569":155,"3572":156,"3577":155,"360":171,"3612":156,"3693":156,"3704":156,"399":[155,175],"3rd":170,"40hz":9,"40x":[131,132],"46m":105,"480":171,"4th":96,"500":[85,175],"501":[155,175],"50m":154,"557":173,"570796":26,"599":[155,175],"5cm":[96,130,131],"5e3":90,"600":[27,154,175],"601":[155,175],"640":171,"65535":[155,175],"699":[155,175],"6core":154,"701":[155,175],"709":155,"710":155,"719":155,"720":155,"729":155,"730":155,"739":155,"785":[99,100,189],"799":175,"7x7":177,"7x9":177,"801":155,"816":154,"842000000":170,"8700":154,"8745":186,"8x10":177,"901":155,"9900":175,"9901":175,"996":170,"9999":[155,175],"abstract":[5,11,28,154,155,188],"boolean":[28,108,155,165,171],"break":[102,153,155],"case":[1,6,12,19,20,22,28,30,31,44,50,54,64,83,84,96,99,101,114,117,124,130,131,132,145,150,152,153,156,158,159,160,161,163,165,168,170,171,172,173,175,178,179,180,181,182,183,185,187,188],"catch":[27,154],"char":160,"class":[28,84,85,87,150,152,153,154,155,158,159,160,161,162,163,173,174,186],"const":[154,158,159,161,163],"default":[15,18,19,20,27,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,65,69,70,71,72,73,75,77,78,79,80,82,83,84,85,87,90,93,94,95,96,97,99,100,101,102,104,105,106,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,144,145,146,149,151,152,154,156,159,160,163,165,167,168,170,171,174,177,178,181,183,187,188],"enum":[95,96,112,116,131,155,175],"export":[144,149,182,184,186,188],"final":[22,23,27,28,94,96,130,131,132,145,153,159,163,171,174,175,176,189],"float":27,"function":[1,3,4,9,11,18,23,27,28,90,91,96,103,105,131,132,152,153,154,155,158,159,160,161,162,163,165,167,168,170,171,172,174,178,179,180,183,185,188],"gin\u00e9":150,"goto":[160,161,162,163],"i\u00f1igo":165,"import":[11,18,27,28,90,96,103,106,144,145,148,163,166,168,171,172,173,174,175,178,179,180,183,185,188,189],"int":[27,75,83,84,85,87,90,92,95,96,101,102,105,107,109,112,116,118,129,130,131,132,159,160,162,163,179],"long":[2,4,9,14,23,28,103,112,116,120,154,163,167,171,174,178],"mart\u00edn":[150,165],"new":[1,4,5,6,8,9,11,14,17,18,19,21,22,24,25,27,28,86,87,96,100,112,116,143,145,146,148,164,165,166,167,168,169,170,171,172,173,174,176,179,181,182,183,184,185,186,188,189,190],"public":[148,160,175],"r\u00f6smann":165,"return":[19,20,22,23,24,25,27,28,52,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,77,80,81,82,96,112,116,130,131,132,151,153,154,155,158,159,161,162,163,165,170,171,173,175,176,179,183,185],"short":[19,58,71,72,73,132,158,171,172,188],"static":[3,28,83,84,85,92,112,116,131,132,148,150,154,156,159,165,168,171,174,175,178,186,187],"switch":[27,96,108,145,146,152,153,154,155,156],"throw":[27,83,91,154,155,179],"transient":[22,24,25,43,46,49,53],"true":[8,20,27,28,30,52,54,65,83,84,85,87,90,91,92,93,94,96,97,99,100,101,102,104,105,107,108,109,110,111,112,113,114,115,116,117,120,122,124,127,128,129,130,131,132,149,153,154,155,156,158,159,160,161,162,163,168,170,171,173,174,175,176,178,180,183,184,185,186,187,189],"try":[19,21,22,24,25,27,84,94,96,106,107,131,132,143,145,149,151,172,173,179,181,183,188],"void":[154,159,161,163],"while":[7,9,13,19,22,24,25,27,87,94,96,99,101,111,141,144,145,146,153,154,155,159,163,167,168,170,171,174,175,176,178,179,182,183,187,188,189,190],ADE:146,Adding:[155,179,190],And:[18,19,156,172,173,176,177,178,183],Are:[112,116,165],Axes:173,BTs:[19,20,165,175,188],BUT:19,DDS:[11,145],For:[0,14,19,20,28,83,84,85,91,92,93,96,99,100,101,103,105,108,111,114,128,131,132,144,145,146,148,149,153,154,158,159,160,161,162,163,165,166,167,168,169,170,171,172,173,174,175,176,178,179,181,183,184,185,186,187,189],GPS:[15,28,170,171],IDE:[146,179],IDEs:[146,179],IDs:163,Its:[96,163,173,178],LTS:149,NOT:[112,116],Near:18,Not:[56,96,150],One:[28,167,170,173],PMs:148,PRs:[13,148,154,155],QoS:[43,46,49,53,115,153,171],ROS:[0,1,2,3,4,6,7,8,9,10,12,13,14,15,20,22,24,25,27,30,31,41,42,44,45,47,48,54,57,93,95,103,143,144,145,146,148,149,150,151,152,153,154,156,158,159,160,161,162,163,165,166,167,169,170,171,172,173,174,175,176,177,178,182,183,184,185,186,188,189,190],SMS:[28,158],Such:145,TLS:186,That:[20,148,153,154,167],The:[0,3,4,6,7,8,9,10,12,13,17,19,20,21,22,23,24,25,26,27,28,30,31,32,33,34,35,36,37,41,42,43,44,45,46,47,48,49,51,52,53,55,56,58,59,68,69,71,72,73,75,77,78,80,82,83,84,85,86,87,88,89,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,114,128,130,131,132,143,144,145,148,150,151,152,153,154,155,158,159,160,161,162,163,165,167,168,169,170,171,172,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],Then:[7,20,153,159,160,161,162,163,170,171,179,180,182],There:[3,14,19,20,28,95,96,143,144,148,151,153,154,160,165,167,171,172,179,183,189],These:[17,18,19,28,96,145,150,151,152,153,154,155,159,160,161,163,167,169,170,171,172,173,174,175,176,179,180,183,185,188],Use:[28,87,90,170,178,181,183,185],Used:[32,33,34,35,36,37,50,83,84,87,108,111,114],Useful:[70,90],Uses:165,Using:[14,83,84,96,100,146,154,165,170,171,174,179,180,190],Will:[20,52,84,165],With:[14,18,28,172,186],Yes:[158,159,160,161,162,163],__cxa_throw:179,__gi_abort:179,__gi_rais:179,__n:179,__node:[179,180],_config:170,_costmap:[153,186],_from_numb:158,_joint:173,_link:173,_m_range_check:179,_nav:174,_to_numb:158,_twilio:158,abi:[96,145],abil:[6,7,28,96,155,187],abl:[0,5,9,14,19,20,154,155,158,159,161,162,163,165,168,170,171,172,174,179,180,188],abort:[153,159,179],about:[4,7,9,11,22,23,24,25,28,83,108,111,114,143,144,145,146,148,150,153,155,156,158,159,160,162,163,170,171,172,173,174,178,179,180,182,185,188],abov:[1,2,3,4,5,6,7,8,9,10,11,12,13,19,20,23,28,82,96,105,113,132,144,151,153,158,161,162,163,167,170,171,172,173,174,175,178,179,180,183,184,185,186,188,189],abrupt:28,abs:161,absolut:[47,48,95,114,152,161,170,173,179,183,185],absurdli:96,academ:6,acc_lim_i:[93,119],acc_lim_theta:[93,119],acc_lim_x:[93,119],accel:170,acceler:[86,99,100,106,119,154,170,174,189],accelwithcovariancestamp:170,accept:[6,61,85,105,131,132,148,163,167,168,181],acceptpendinggo:163,access:[0,28,145,146,153,154,159,171,173,179,188],accommod:145,accompani:90,accomplish:[8,158,165,170,173,179],accord:[28,95,170,171,183,185],accordingli:[9,84,183,185],account:[28,83,84,153,154,158,167,174,178],account_sid:158,accur:[6,28,83,84,153,170,174],accuraci:[26,84,151],achiev:[11,90,96,99,103,106,107,153,154,155,156,173,174],acircl:177,ackerman:167,ackermann:[103,150,153,165,167,174],ackermannconstrain:96,acknowledg:87,acquir:28,across:[18,28,96,102,110,131,132,145,155,163,166,171,172,174,188],act:[9,14,28,130,152,153,169,171,173,183,187,189],action:[11,17,19,27,30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,52,54,57,75,77,78,79,80,83,84,86,87,91,96,104,107,149,150,151,155,158,159,163,165,167,170,171,172,173,174,175,176,181,182,183,185,188],action_a:20,action_b:20,action_c:20,action_nam:159,action_typ:[83,84,187],actionnod:20,actionnodebas:159,actiont:163,activ:[12,27,28,58,71,72,73,84,94,143,148,149,152,153,154,155,158,161,162,163,170,171,174,175],actual:[19,52,84,90,96,100,154,163,168,172,173,174,177,182,187,189],actuat:145,adapt:[6,28,85,99,153,165,171,172,173],add:[0,2,8,17,74,75,76,77,78,79,80,81,82,90,96,111,112,116,145,148,152,153,154,155,156,158,163,168,170,171,172,173,174,175,176,179,180,184,186,187,188],add_act:[183,185],add_compile_opt:[179,180],added:[10,13,22,24,25,87,96,145,148,151,152,153,154,155,156,158,160,161,162,163,167,168,171,172,173,174,175,180,186,187,189],adding:[1,9,85,131,132,145,154,155,170,171,173,175,178,183,185],addit:[3,11,17,20,22,23,24,25,28,84,89,144,145,153,154,155,159,163,167,170,171,173,179,180],addition:[0,11,28,145,146,151,152,153,163],address:[32,33,34,35,36,37,41,42,45,151,152,153,154,155,156,158],adequ:174,adher:172,adjac:[105,109,178],adjust:[9,11,28,29,77,80,82,84,96,106,155,156,173,185,187],admiss:[131,132,154],admittedli:11,advanc:[0,28,166,174],advantag:[12,28,155,189],advic:[167,174],advis:[22,24,25,28,170],affect:[83,89,153,154,156,173],aforement:96,after:[2,10,21,22,24,25,27,28,84,85,87,96,100,101,106,115,117,124,129,130,131,132,148,149,153,154,160,161,162,163,168,170,171,173,174,175,177,178,179,180,181,183,185,186,188,189],afterward:170,again:[19,20,21,23,75,143,145,149,151,166,170,173],against:[58,71,72,73,132,155,174],agent:[84,174],aggreg:175,aggregation_typ:[134,135,138,139],aggress:84,agre:148,agreement:148,ahead:[86,96,99,121,122,134,138],aid:[2,23],aim:[1,7,9,10,13,106,169,173,174,180],aisl:[28,130,154,167,174],aislewai:154,aitor:165,alarm:[83,156],alberto:165,aleksei:165,alexei:[14,150,165],alexeymerzlyakov:14,algorithm:[3,15,17,18,22,24,25,28,90,96,99,101,102,103,148,150,151,153,154,155,156,160,161,165,168,171,173,174,176,178,180],alias:28,align:[117,134,138,139,156],alik:14,aliv:14,all:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,17,18,19,20,27,28,39,74,84,85,86,94,96,99,101,103,105,106,109,113,136,144,145,146,148,150,151,152,153,154,158,161,162,163,165,167,170,171,172,173,174,175,176,177,179,180,183,185,186,188,189],allevi:174,alloc:[28,175,179,186],allot:[1,9,11],allow:[5,6,8,9,10,17,18,19,20,22,23,24,25,28,79,84,85,86,87,96,97,99,105,114,130,131,132,133,136,141,145,146,148,150,152,153,154,158,160,161,162,167,170,171,172,173,174,175,177,178,179,181,183,185],allow_revers:99,allow_reverse_expans:132,allow_unknown:[97,105,130,131,132,153,162],almost:[152,154],along:[14,27,28,56,66,82,96,99,100,108,111,114,131,132,136,152,153,154,155,165,167,171,173,175,176,179,183,185],alongsid:[163,174],alot:96,alpha1:85,alpha2:85,alpha3:85,alpha4:85,alpha5:85,alpha:[173,183],alreadi:[4,7,96,152,153,154,158,168,170,173,174,179],also:[1,3,4,6,7,11,17,19,20,21,22,23,24,25,27,28,83,84,85,86,88,91,92,94,95,96,99,101,103,104,107,131,132,144,145,146,148,149,150,151,152,153,154,155,156,158,159,160,161,162,163,167,168,170,171,172,173,174,175,176,177,178,179,180,183,184,185,186,187,189],alter:145,altern:[3,23,28,56,145,146,153,168,170,179],although:146,alwai:[9,16,21,70,83,84,94,106,132,143,153,154,173,174,183,189],always_on:[170,171],always_reset_initial_pos:85,always_send_full_costmap:[92,171],alwayson:171,ambigu:99,amcl:[6,7,17,27,28,29,50,63,149,150,152,165,171,172,174],amcl_pos:151,amclnod:154,amend:148,ament:[158,160,161,162,163,177],ament_cmak:[158,161,162,163,173],ament_cppcheck:148,ament_cpplint:148,ament_index_cpp:163,ament_index_python:[183,185],ament_uncrustifi:148,among:[17,28,105,167,174,178],amongst:173,amount:[92,113,123,125,127,129,130,131,132,141,152,153,155,183],ampl:[22,24,25],analog:[8,84,153,155,159,179,189],analysi:[7,28,148,150,180],analyt:[131,132,153,154],analytic_expansion_max_length:[131,132,154],analytic_expansion_ratio:[131,132],analyz:[5,6,7,10,27,28,159,180],andrei:165,angl:[27,28,54,83,84,105,123,130,131,153,165,174],angle_quantization_bin:131,angular:[56,84,96,99,100,118,119,122,131,134,137,138,140,155,161,170,174,189],angular_dist_threshold:[100,189],angular_distance_weight:56,angular_granular:[93,122],angular_limit:[84,155],angular_vel:161,angular_veloc:170,ani:[0,3,9,11,14,17,19,20,21,23,28,43,46,49,51,53,58,60,74,83,84,91,94,96,99,102,103,105,111,112,116,131,143,145,146,148,150,152,153,154,155,156,158,159,160,161,162,163,165,167,171,172,173,174,175,176,178,179,180,181,183,185,187,188,189],anim:[4,178],annot:[28,153,160,161,162,183,185],announc:148,anoth:[0,1,4,6,10,21,22,24,27,28,58,83,103,130,131,145,148,153,154,156,159,165,167,168,170,171,173,176,179,181,183,184,185,186],anshumaan:165,answer:[0,148,153],anybot:5,anyhow:154,anyon:11,anyth:[21,28,83,153,159,160,163,174,183,188],anywai:174,anywher:[146,154],apach:[1,2,3,4,5,6,7,8,9,10,11,12,13,148],apart:[23,189],apex:146,api:[18,28,52,150,151,153,158,160,163,171,176],appear:[84,148,149,153,154,155,171,173,177,178,182,187,188],append:[145,148,170,171],appli:[0,7,11,28,96,99,102,105,106,111,130,131,132,140,146,153,159,172,173,174,178,179,180,184,185],applic:[1,3,6,10,12,14,18,19,22,23,24,25,27,28,56,83,84,90,96,143,145,151,154,155,158,160,163,165,167,174,175,178,179,180,181,185,186,188,189],appreci:[28,148],approach:[23,28,79,84,96,97,99,103,105,130,131,132,150,153,155,156,165,167,170,174,176,187,189],approach_velocity_scaling_dist:99,appropri:[2,19,91,96,98,106,114,148,154,155,163,167,170,172,173,174,179,187,188],approv:[3,148],approxim:[84,100,106,130,149,155,167,168,174,177,189],apt:[144,145,149,170,171,173,177,180,184,186],arbitrari:[84,103,146,165,167,169,174],arbitrarili:150,arc:[83,84,171],architectur:[11,153],area:[3,7,28,38,39,84,92,108,111,113,114,130,131,132,148,153,154,155,158,160,165,171,173,174,177,180,183,185],areerrorcodespres:[88,155],arg:[144,177,179,180],argc:179,argument:[27,144,154,155,156,159,161,170,173,176,179,180,183,185],argv:179,arm:158,aroun:155,around:[9,14,19,23,28,38,56,79,83,84,90,92,96,99,110,148,150,153,165,171,172,173,174,177,184,189],arrai:[90,131],arriv:[107,128,153,165],arrow:[173,182],art:103,articl:[150,175],artifact:[101,103,145,178],artifici:96,as_str:163,asid:[170,171],ask:[0,3,28,148,160,179,188],asla:14,aspect:[20,145,146,176,177],assembl:188,assess:174,asset:179,assign:[28,52,56,90],assist:[0,27,30,148,165,174],assisted_teleop:[32,86],assisted_teleop_error_cod:30,assisted_teleop_serv:30,assistedteleop:[27,32,88,154,155,165],associ:[28,155,170,171,172],assum:[19,20,146,153,160,161,165,168,172,173,178,179,183,184,185,186,187,188],assumpt:[106,174,184],asymmetr:90,async_slam_toolbox_nod:171,asynchron:[19,20,28,152],ata:[128,165],atom:13,attach:[148,170,171,172,175],attempt:[1,19,21,22,24,25,28,79,94,95,96,102,130,131,132,146,156,179,183],attempt_respawn_reconnect:94,attent:[28,96,174],attest:148,attract:96,attribut:[96,155,183],auth_token:158,author:[146,148,150],auto:[145,161,163],auto_start:182,autom:[144,145,146],automat:[18,96,99,113,145,148,153,154,168,170,172,173,174,175,183,185],autonom:[1,27,28,96,99,150,153],autonomi:[1,27,28,151,154,155,175,188],autostart:[27,94,149,174,175,182,183,185],auxiliari:27,avail:[5,9,27,28,70,83,84,96,99,105,143,144,146,148,151,153,154,160,165,167,170,171,174,175,176,177,179,181,186],averag:[83,84,85,105],avoid:[1,28,84,89,90,92,96,111,132,145,150,153,154,160,167,168,170,171,172,173,174],awai:[21,90,96,100,130,155,171,177,188,189],awar:[22,24,25,90,96,103,105,131,132,153,171,174],awkward:[96,174],axes:106,axi:[27,106,160,173],back:[1,9,22,24,25,27,28,31,90,96,100,108,132,148,151,154,155,159,161,162,163,165,172,173,174,188],back_up:86,background:[95,152,154,173,174,183],backport:96,backtrac:[155,190],backup:[1,19,20,22,23,24,25,27,33,88,151,154,155,158,165],backup_dist:[19,22,23,24,25,27,31,88,153],backup_error_cod:31,backup_serv:[31,44],backup_spe:[19,22,23,24,25,27,31,88,153],backward:[56,117,137,140,153,155,179],backward_ro:179,bad:[22,24,25,28,85,158],bake:174,balanc:[96,102],ball:28,band:[3,151,167,189],bar:[173,177,188],barrier:14,base:[2,5,6,9,17,19,21,28,51,56,59,61,77,82,83,84,85,86,87,90,92,95,96,101,103,104,108,111,114,123,133,134,135,136,138,139,144,145,146,148,150,151,153,154,155,156,158,159,161,162,163,165,167,170,171,172,173,174,178,179,183,185,186,187,188],base_:173,base_class_typ:[158,160,161,162,163],base_footprint:[83,84,85,173,187],base_frame_id:[83,84,85,187],base_height:173,base_joint:173,base_las:172,base_laser2:172,base_length:173,base_link:[28,51,56,59,61,70,77,86,87,92,101,102,104,158,159,160,163,168,170,171,172,173,176],base_link_fram:170,base_shift_correct:[83,84],base_width:173,baselin:[96,131,171],baseobstacl:93,baseobstaclecrit:93,bash:[143,144,145,149,160,168,170,171,173,182,183,184,185],bashrc:[143,145],basi:[5,96,174],basic:[4,5,17,18,19,27,28,132,151,153,154,160,163,167,168,169,170,171,172,179,186],basic_class_typ:160,basicnavig:[27,154],basket:27,batch:96,batch_siz:96,batteri:[19,20,28,64,65,154,155,165,181],battery_statu:[64,65],battery_top:[64,65],batteryst:[64,65],beam:85,beam_skip_dist:85,beam_skip_error_threshold:85,beam_skip_threshold:85,beamskip:85,beauti:179,becam:153,becaus:[23,28,94,96,145,146,148,153,158,170,172,174,179,180,182,188,189],becom:[4,11,18,19,28,94,96,105,151,154,170,172,173],been:[4,6,14,17,19,20,22,24,25,28,51,59,83,89,96,103,145,148,152,153,154,155,156,160,161,162,165,168,171,172,173,174,180,186,187],befor:[5,11,19,22,23,24,25,26,28,43,46,49,53,59,75,77,79,84,85,91,95,96,102,111,112,116,127,130,131,132,140,145,146,151,152,153,154,158,159,160,161,162,163,165,167,170,171,173,174,175,176,178,179,180,182,183,184,185,186,188,189],beforehand:11,begin:[131,132,154,161,163,170,173,175,189],beginn:[173,179],behalf:148,behav:154,behavior:[1,2,3,11,17,20,21,22,23,24,25,26,29,30,31,32,33,35,36,37,43,44,46,47,48,49,54,57,59,61,74,75,76,79,83,84,96,99,100,103,107,145,150,151,161,163,164,167,170,175,176,186,189,190],behavior_plugin:[86,154,158],behavior_serv:[86,94,154,158,175],behavior_tre:[19,27,47,48,87,152,156,163,188],behaviortre:[18,19,20,21,22,23,24,25,26,28,60,88,159,165,181,188],behaviortreenavig:[87,155,163],behaviour:[152,153,185],behavor:153,behind:[154,185],being:[0,6,8,11,19,22,24,25,28,54,84,90,95,96,108,114,131,132,145,152,153,156,161,163,167,168,170,171,174,175,179,183,185,187],believ:20,belong:[28,114,153,183,185],below:[0,4,9,11,13,16,18,19,20,23,27,28,65,82,87,89,91,93,96,100,101,103,105,107,112,113,116,126,141,148,150,153,154,155,158,159,160,161,162,163,165,168,170,171,172,173,175,176,177,178,179,180,181,182,183,185,187,188,189],belt:179,benchmark:[4,7,11],benefici:[2,28,96,111,163,179],benefit:[7,145,174],benign:146,berth:174,bespok:154,best:[6,8,11,28,29,84,96,117,130,131,132,145,148,154,155,167,171,172,174,178,179,183,186],better:[22,24,25,28,83,84,99,105,145,153,154,156,171,174,175,180,185,189],between:[14,19,27,28,83,84,85,88,96,97,99,101,105,130,131,132,145,146,150,152,153,154,155,156,157,163,167,168,170,171,172,173,174,183,188,189],bewar:155,beyond:[149,159,174,185],bezier:90,bias_mean:170,bias_stddev:170,bidirect:156,big:19,bin:[131,132,154],binari:[28,92,95,130,149,155,158,159,161,162,163,165,186],binary_filt:108,binary_st:108,binary_state_top:108,binaryfilt:108,bind:[90,163],bit:[19,154,174,179],black:[171,176,178,183],blackboard:[18,41,42,45,47,48,52,60,61,62,79,87,154,155,159,163,175,176,188],blacker:183,blanco:165,blank:162,blasco:165,blind:[99,153],blink:83,blob:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],block:[12,13,27,28,143,154,160,162,170,173,174,186,189],blocki:132,blog:8,blue:188,bmp:[183,185],board:[28,177],bodi:159,bog:179,bogu:95,boiler:158,boilerpl:[158,163,169],bond:[94,152,171],bond_client_node_:154,bond_respawn_max_dur:94,bond_timeout:[94,153,175],bond_timeout_m:153,book:28,booktitl:150,bool:[52,54,83,84,85,87,90,92,94,96,97,99,101,102,105,106,107,108,109,110,111,112,113,114,115,116,117,120,122,124,127,128,129,130,131,132,133,136,153,158,163],both:[1,7,11,19,22,23,24,25,27,28,83,84,99,103,150,153,154,156,159,163,167,168,170,171,173,174,178,179,180,183,184,185,186,187,189],bottleneck:180,bottom:[149,168,171,177,179,180,182],bound:[9,56,84,99,102,130,131,132,154,160,187],boundari:[154,185],box:[1,9,28,84,107,154,155,168,170,171,173,174,186,187,188],box_inertia:[170,173],bpwilcox:14,branch:[5,13,23,131,132,143,144,145,148,154,176],breakdown:174,breakpoint:179,breez:173,breviti:[158,189],brian:[14,165],brief:[103,154,170,171,172,173],briefli:146,bring:[27,84,94,154,156,173,184],bringup:[27,28,94,144,149,154,155,160,167,169,171,174,175,187],bringup_launch:182,broad:[2,7,169,174],broadcast:170,broken:19,brother:158,brows:188,browser:[144,146],bsd:148,bt_action_server_:163,bt_loop_dur:87,bt_navig:[27,47,48,59,61,87,94,152,155,156,159,163,175],bt_plugin:[152,153],bt_register_nod:159,bt_xml_filenam:163,btactionnod:159,btstatu:163,budyakov:165,buffer:[28,86,104,106,112,116,158,161,162,186],bug:[14,148,166],buggi:188,build:[1,5,7,10,14,18,19,27,28,146,147,149,150,154,155,158,159,160,161,162,163,172,178,179,180,181,183,185,186,187],build_test:173,build_typ:[158,161,162,163],builder:[145,159],buildtool_depend:173,buildx:145,built:[11,145,148,160,168,169,170,171,173,177,178,179,183,184,185,186,187,189],builtin_interfac:175,bulldoz:28,bunch:143,burden:174,busi:28,button:[149,155,160,161,162,163,168,171,177,181,182],bypass:[84,89,183],c_str:[162,163],cach:[131,132,144,145,154],cache_obstacle_heurist:[131,132,174],cachefrom:145,calcul:[19,27,83,84,108,154,160,161,162,170,178],calendar:148,calib_cb_fast_check:177,calibr:[18,190],calibrationdata:177,call:[17,27,28,38,39,40,84,91,98,131,132,137,148,149,151,152,153,154,155,158,159,160,161,162,163,165,172,173,174,175,176,179,180,183],callabl:160,callback:[11,13,28,153,163],callback_group:154,caller:[22,24,25],callgrind:180,came:153,camera:[28,108,128,155,171,186,190],camera_calibr:177,camera_depth_fram:171,camera_depth_joint:171,camera_image_topic_nam:128,camera_joint:171,camera_link:[171,172],camera_nam:177,cameracalibr:177,can:[0,1,3,4,5,6,7,8,11,13,14,17,18,19,20,22,23,24,25,26,27,28,29,32,33,34,35,36,37,41,42,45,75,77,78,80,82,84,85,87,88,89,90,91,95,96,99,100,101,103,105,107,112,116,131,132,143,144,145,146,148,149,150,151,152,153,154,155,156,158,159,160,161,162,163,165,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],cancel:[17,21,23,27,32,33,34,35,36,37,149,159,163,165,181],cancelassistedteleop:[88,154],cancelbackup:88,cancelcontrol:[23,88,154],canceldriveonhead:88,cancelingcontrolandwait:23,cancelnav:154,cancelspin:88,canceltask:27,cancelwait:88,candid:[1,7,96,148,167],cannot:[28,70,96,99,106,131,132,137,153,155,163,175,186,188],canon:28,capabl:[4,7,10,15,27,145,146,150,153,166,171,181,189],captur:[28,154,167,180],car:[103,150,153,165,168,174],care:96,career:11,carefulli:167,carl:[14,165],carlo:[6,28,85,171],carri:[28,152,153,154,162,181],carrot:21,cart:4,cartesian:96,cartograph:151,cast:7,caster:173,caster_joint:173,caster_xoff:173,catchi:8,categori:167,cater:154,cati:181,caus:[23,31,44,83,84,85,96,131,132,149,154,174,178,183,185],caution:[146,178],ccach:[144,145],ccw:26,ceas:84,cell:[27,28,105,109,110,112,113,116,154,160,167,168,171,173,178,183,185],center:[19,28,38,39,96,111,130,131,132,154,158,168,172,173,177,182],central:28,cerescostawaresmooth:[104,176],certain:[20,152,154,160,167,169,171,181],certif:[84,147],certifi:[9,84,148],chain:185,challeng:28,chanc:[1,7,9,20,154],chang:[6,11,12,13,14,17,18,19,22,24,25,27,28,60,62,74,84,90,96,102,106,124,130,131,132,134,138,145,148,149,152,160,161,163,166,168,170,171,174,179,181,182,183,185,186,188],change_penalti:[131,132],changemap:27,channel:148,chao:148,chapter:[28,183,185],charact:101,characterist:[4,12,102,170],charg:[28,64,155,165,167],charger:28,charuco:177,chassi:[172,173],chat:148,check:[0,7,9,11,14,19,20,23,27,28,51,52,58,60,61,62,64,65,66,68,70,71,72,73,79,83,86,87,88,90,91,92,96,99,100,104,107,111,123,124,125,126,137,143,144,145,146,148,150,152,153,154,158,159,160,161,162,163,165,167,168,170,171,172,174,177,178,179,182,183,185,189],check_for_collis:[27,52],checker:[18,45,91,117,151,158,189],checkerboard:177,checklist:169,checkout:[99,144],chessboard:177,child:[19,20,23,70,74,75,77,80,81,82,154,165,170,171,172,173],child_frame_id:170,children:[19,20,23,74,75,76,79,165,180],chip:174,choic:[10,27,28,174,175,184],choos:[105,145,146,149,163,168,172,174,178,179,185],chosen:[27,28,145,155,185],christoph:165,chronicl:145,chug:179,cilqr:3,circl:[20,83,84,174,177,187],circular:[96,103,150,156,167,168,173,174],cite:[99,150],citizen:186,cla:[1,2,3,4,5,6,7,8,9,10,11,12,13],claim:148,class_list_macro:[158,160,161,162,163],classic:174,classification2d:171,classification3d:171,clavero:150,clean:[28,96,145,152,154,158,161,162,163,174],cleaner:173,cleaningup:175,cleanli:[28,94,163,174,180],cleanup:[158,161,162,163,175],clear:[19,20,22,23,24,25,27,28,38,39,40,92,112,113,116,148,153,154,155,162,165,171,177,186],clear_after_read:186,clear_around_:153,clear_around_local_costmap:38,clear_entirely_global_costmap:[19,22,23,24,25,88,159],clear_entirely_local_costmap:[19,22,23,24,25,40,88,159],clear_except_:153,clear_except_local_costmap:39,clear_on_max_read:[113,171],clear_threshold:113,clearallcostmap:27,cleararoundrobot:154,clearcostmaparoundrobot:88,clearcostmapexceptregion:88,clearcostmapservic:20,clearentirecostmap:[19,22,23,24,25,88,153,159],clearer:171,clearexceptregion:154,clearglobalcostmap:[19,22,23,24,25,27,88,159],clearing_endpoint:153,clearingact:[19,22,23,24,25,88],clearlocalcostmap:[19,20,22,23,24,25,27,38,39,40,88,159],clever:179,cli:[28,95,145,146,152,153,180,184],click:[16,146,149,160,161,162,163,168,171,177,182,188],clicked_point:181,clicked_point_to_pos:181,client:[20,28,151,153,154,158,159,163,176],client_nod:154,client_node_:154,clinet_node_:154,clip:[171,183],clock:[183,185],clock_:[161,163],clone:[144,177,181,183,184,185,186],cloned_tb3_simulation_launch:156,close:[23,28,51,79,83,84,92,96,99,106,132,135,141,145,153,154,161,168,174,187],closed_loop:106,closer:[55,96,131,155],closest:[56,99,117],cloud:[7,28,145,146,149,152],cmake:[158,160,161,162,163,177,180],cmake_build_typ:180,cmakelist:[158,160,161,162,163,170,171,173,179,180],cmd:[170,171],cmd_vel:[13,83,84,161,170,180,187],cmd_vel_in_top:[84,187],cmd_vel_nav:180,cmd_vel_out_top:[84,187],cmd_vel_raw:[84,187],cmd_vel_teleop:86,code:[5,6,15,30,31,41,42,44,45,47,48,52,54,58,71,72,73,85,86,87,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,106,107,145,146,148,151,152,154,158,159,160,161,162,163,165,168,170,171,173,176,178,179,186,189],codebas:148,codecov:12,codespac:[145,146],codifi:145,coeffici:[114,177,183,185],coffe:[146,188],colcon:[144,145,160,168,170,171,173,179,180,183,185],collabor:[4,14,148],collect:[27,169,171,180],collid:[4,9,168],collis:[1,7,9,28,29,30,52,86,90,92,96,99,100,104,111,141,150,151,153,154,158,165,166,167,168,170,171,173,174,189,190],collision_cost:96,collision_detector:83,collision_detector_st:[83,156],collision_margin_dist:96,collision_monitor:[84,187],collision_monitor_nod:187,collision_monitor_param:187,collision_monitor_st:84,collisionmonitor:155,color:[8,90,128,171,173,174,178,183,185,186],color_dark:183,color_light:183,column:[116,171],com:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],combin:[28,92,134,135,138,139,153,184],combination_method:[92,112,116,156,186],come:[8,13,14,28,96,99,126,148,154,155,158,161,162,163,170,172,173,187],command:[1,9,17,23,30,43,46,49,53,78,99,100,106,144,145,146,150,152,158,160,161,162,163,165,167,170,171,172,173,179,181,182,183,184,185,189],commandlin:[95,179,180],comment:[145,148,154,160,162,179,186],commerci:[28,148],commit:[145,148,166,177],common:[19,27,28,96,145,146,150,153,154,163,170],commonli:[20,43,46,49,53,163,171],commun:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,17,28,145,148,150,158,163,172,174,175,177],compani:[148,150,174],companion:188,compar:[28,58,71,72,73,87,90,103,155],comparison:[14,150],compat:170,compet:148,compil:[145,146,158,161,162,163,176,179,180],complement:[5,152],complementari:175,complet:[3,4,5,12,17,19,20,23,27,28,52,84,96,99,100,124,131,132,141,145,148,149,150,151,152,153,154,155,156,158,159,163,166,167,168,170,171,173,175,176,177,180,182,184,186,188,189],complex:[17,28,87,96,150,155,171,172,173,179,188],complexyolo:4,compli:[2,167,170],complianc:106,compliant:172,complic:150,complimentari:163,compon:[6,17,74,75,76,77,78,79,80,81,82,105,106,140,153,154,169,173,175,183,185],component_contain:175,component_container_isol:154,componentcontain:179,compos:[11,154,160,174,175,179,180],composable_node_descript:175,composablenod:[175,187],composablenodecontain:175,composit:[166,179,180],composition_demo:175,comprehens:145,compris:[13,173],comput:[7,17,18,19,20,21,22,28,41,42,96,98,99,103,105,130,131,132,134,138,150,154,155,158,159,161,162,165,167,168,170,171,172,174,176,180,182],computation:[28,116,154],compute_path_error_cod:[41,42,87,176],compute_path_error_code_id:175,compute_path_through_pos:[155,175],compute_path_to_pos:[155,175],compute_path_to_pose_error_cod:72,computeandpublishveloc:153,computeandsmoothpath:176,computepaththroughpos:[22,88],computepaththroughposesrecoveryfallback:22,computepathtopos:[18,19,20,21,23,24,25,49,51,77,80,82,88,159,163,176,181],computepathtoposeact:49,computepathtoposerecoveryfallback:[19,24,88],computevelocitycommand:[91,161],concaten:153,concept:[7,19,20,150,153,167,171,172,175,183,185,188],conceptu:172,concern:[146,148,154],conclus:23,concret:172,condit:[12,19,22,24,25,28,30,31,44,54,66,67,70,102,145,154,155,159,165,170,173,188,189],conditionnod:159,conf:159,confer:150,config:[145,146,168,170,171,173,179,184],configur:[0,1,14,16,17,18,19,20,27,28,43,46,49,53,59,83,84,89,90,91,92,94,95,96,103,108,111,114,144,145,146,151,152,154,155,156,158,159,161,162,163,165,169,173,174,175,176,178,179,181,182,184,186,188],configured_param:[175,183,185,187],confin:[96,145,156,168],confirm:[168,171,177],conflict:152,conform:150,confus:20,conjunct:[27,96],connect:[14,20,28,94,97,105,109,130,145,146,152,153,154,165,167,170,171,172,173,178,188],consequ:23,consid:[3,14,19,30,31,44,54,83,84,85,87,88,92,96,126,131,132,141,148,152,153,155,158,159,161,162,163,165,167,174,175,183],consider:[4,96,174],consider_footprint:96,consist:[8,18,146,148,153,154,165,170,171,172,174,175,188],consol:187,constant:[20,99,161,173,174],constantli:[152,154],constrain:[29,102,153,165,174],constrainedsmooth:[90,154],constraint:[22,100,106,153,154,163,165,167,174,189],constraintcrit:96,construct:[28,148,154],constructor:[28,154,159],constsharedptr:163,consult:14,consum:[9,154],contact:[1,2,3,4,5,6,7,8,9,10,11,12,13,148,150,174,175],contain:[9,11,18,22,24,25,28,45,48,89,96,103,106,132,147,151,152,153,154,155,156,158,160,161,162,163,165,170,171,173,174,175,176,177,179,183,187,189],container:145,containeris:145,content:[146,168,169,171,173],context:[11,13,19,20,22,23,24,25,88,144,159,165,188],contextu:[18,19,22,24,25,150,155],continu:[1,12,19,20,21,22,23,24,25,28,96,107,129,131,132,146,148,149,150,151,152,153,154,155,163,170,173,174,184],contractor:14,contrast:154,contribut:[1,2,3,4,5,6,7,8,9,10,11,12,13,28,148,171,174,175],contributor:[14,148],control:[2,4,7,9,11,13,17,18,19,21,22,23,24,25,27,29,34,43,45,55,56,71,72,73,75,76,77,78,82,84,92,99,103,106,114,118,119,120,121,122,123,124,125,126,132,133,134,135,136,137,138,139,140,141,142,150,151,152,156,158,159,160,163,164,166,169,170,173,175,176,179,180,181,182,184,185,186,187,188,190],controlcancel:23,controller_frequ:[91,93,96,99,100,189],controller_id:[19,21,22,23,24,25,27,43,45,88,153,159,181],controller_pati:153,controller_plugin:[91,93,99,100,152,161,167,189],controller_plugin_id:[117,118,119,120,121,122,133,134,135,136,137,140,141,142],controller_selector:43,controller_serv:[23,91,93,94,96,99,100,152,153,154,161,167,175,180,185,187,189],controllerselector:[22,24,25,88,153],controllerserv:[154,187],controlnod:159,conveni:[146,185],convent:[22,24,25,28,171,172,175],converg:[85,90,96],convers:[27,95,148,183,185],convert:[0,96,114,131,132,150,151,153,162,172,183,185],convert_typ:[183,185],convex:96,cooper:2,coordin:[5,27,28,85,92,154,170,172,173,181],copi:[154,168,170,171,173,176,179,183,185,186],copyright:148,core:[7,18,28,150,155,175,176],corner:[99,149,153,177,183,188],corpor:14,correct:[28,83,84,143,145,148,154,170,171,173,182,183,185,187],correctli:[20,28,149,153,154,168,170,171,172,183,185,187],correl:145,correspond:[28,79,83,84,87,96,97,105,108,109,110,111,112,113,114,115,116,130,131,132,153,154,158,159,160,171,172,178,185],correspont:183,corridor:[96,167,174],cost:[9,19,27,28,83,84,86,90,92,96,99,103,105,111,120,130,131,132,145,153,154,160,165,171,174,178],cost_check_point:90,cost_cloud:153,cost_penalti:[131,132],cost_pow:96,cost_scaling_factor:[92,96,105,110,160,171],cost_travel_multipli:130,cost_weight:96,costamp2d:183,costli:28,costmap2d:[143,164,165,178,183,185],costmap2dro:[154,161],costmap:[1,2,4,5,7,10,19,20,21,22,24,25,29,38,39,40,84,86,89,90,99,104,105,108,110,111,112,114,116,130,131,132,133,136,150,151,154,160,161,162,167,168,174,178,190],costmap_2d:[5,17,160,171],costmap_2d_cloud:153,costmap_2d_ro:115,costmap_:[160,162],costmap_filter_info:[95,108,111,114,183,185],costmap_filter_info_serv:[95,183,185],costmap_filters_demo_dir:[183,185],costmap_raw:[86,101,102,104,158,176],costmap_ro:[154,161,162],costmap_ros_:161,costmap_top:[101,102,104,158,176],costmapfilt:153,costmapfilterinfo:[108,111,114,183,185],costmapinfotyp:155,could:[1,2,3,6,7,9,10,21,28,83,84,91,105,145,146,152,153,154,155,159,160,161,165,172,174,176,179,181,183,185,186,187],couldn:179,count:[96,154,170,177,183],counter:[30,103,154,159,163,170],counterpart:174,coupl:[27,189],cours:[5,11,145,173],covari:85,cover:[2,28,113,148,153,167,174,175,179,183,185],coverag:[3,4,6,12,28,163,166],cpp:[19,28,151,152,153,154,159,160,165,179,188],cpu:[4,7,84,145,154,174,175],crash:[28,94,152,154,174,175,188],crdelsei:14,creat:[1,4,5,6,8,9,10,11,13,14,22,23,24,25,28,41,42,76,79,84,92,94,96,102,103,144,146,148,150,151,152,153,154,155,160,165,167,168,170,171,172,173,174,175,178,182,183,185,186,187,188,189],create_cli:163,create_subscript:163,createplan:162,creation:[9,152,174],creativ:[6,8],creator:165,criteria:[28,124,141,148,154,165],criterion:90,critic:[1,7,9,28,117,133,134,135,136,137,138,139,140,141,142,151,167,174,175,179],critical_weight:96,cross:[143,145,150,167,168],crowd:[22,24,25,167],crtl:[145,146],crux:19,ctrl:145,cube:[168,171],cubic:90,cuda:7,cull:[22,51,165],current:[3,9,11,12,14,19,20,25,27,28,44,51,56,60,77,80,82,83,84,96,98,99,100,106,107,108,111,113,114,132,148,150,152,153,154,155,158,159,161,162,163,165,170,171,172,173,174,175,181,187,188,189],current_path:163,current_pos:163,curv:[105,160,174],curvatur:[96,99,131,153,161,167],curvature_lookahead_dist:[99,155],curvature_smooth:[104,176],cusp:[90,96,99],cusp_zone_length:90,custom:[10,18,19,20,22,24,25,27,28,55,56,76,78,85,86,87,96,103,107,132,144,145,146,150,154,155,158,161,162,163,165,167,169,171,186],customiz:155,cut:[131,132],cxprime:171,cyan:[90,173],cycl:[23,83,84,99,131,132,154,158],cycle_frequ:[86,158],cylind:[171,173],cylinder_inertia:173,dai:11,damag:106,danger:[90,150,187],dark:183,darker:185,dash:149,data:[1,4,7,9,10,27,28,83,84,87,89,96,102,112,113,116,130,131,132,145,150,153,155,156,165,170,171,172,175,177,180,183,185,186,187],data_typ:[92,112,116,171,186],date:[83,84,85,108,111,114,148,151],david:[14,93,165],dcmake_build_typ:180,dco:147,deactiv:[28,94,158,161,162,163,175],dead:28,deadband:[106,154],deadband_veloc:106,deal:[7,28,170,172,174],dealloc:28,dealt:19,debug:[28,90,96,116,117,120,131,145,155,179,180],debug_optim:90,debug_trajectory_detail:[93,117,161],debug_visu:[131,156],debugg:[145,179],debuggin:96,decad:[6,14],decai:[85,96,110,165,171],decay_acceler:186,decay_model:186,decel_lim_i:[93,119],decel_lim_theta:[93,119],decel_lim_x:[93,119],deceler:[119,156],decemb:[103,174,186],decent:96,decid:[23,85,156,172,173,175],decis:168,declar:[59,61,145,148,153,158,160,161,162,183,185],declare_autostart_cmd:[183,185],declare_mask_yaml_file_cmd:[183,185],declare_namespace_cmd:[183,185],declare_paramet:163,declare_parameter_if_not_declar:[161,162],declare_params_file_cmd:[183,185],declare_use_sim_time_cmd:[183,185],declarelaunchargu:[170,173,183,185],declareparamet:160,decod:185,decor:[19,21,23,154,159,165,181,188],decoratornod:159,decreas:[96,155,186,187],decrement:160,dedic:14,deduc:179,deeper:[96,171],deepli:188,def:[154,173,183,185],default_bt_xml_filenam:[87,152,159,163,181],default_control:43,default_critic_namespac:117,default_goal_check:46,default_model_path:173,default_nav_through_poses_bt_xml:[87,163],default_nav_to_pose_bt_xml:[87,156,163],default_plann:49,default_rviz_config_path:173,default_server_timeout:87,default_smooth:53,default_st:108,default_valu:[170,173,183,185],defaultsto:170,defin:[1,5,9,10,19,27,28,43,46,49,53,58,59,61,79,83,84,86,87,91,92,95,96,98,104,107,117,118,119,120,121,122,123,124,125,126,127,128,129,133,134,135,136,137,138,139,140,141,142,145,151,152,153,154,155,159,160,162,163,167,168,170,171,172,173,175,178,179,182,183,185,186,188],definit:[28,45,52,87,155,158,160,163,170,171,173,175],deg:96,degrad:131,degre:[11,26,83,84,131,153,156],delai:[83,84],delet:[154,170],deliv:27,deliveri:1,deloc:50,delsei:[14,165],delta:105,demand:[28,161,162],demo:[8,10,23,28,154,168,175,183,185],demo_inspect:27,demo_pick:27,demo_secur:27,demonstr:[4,10,27,144,154,160,186,187],deni:163,denois:[92,165],denoise_lay:[109,178],denoiselay:[109,178],denot:[171,179],dens:27,dense_qr:90,densiti:[85,96],depend:[19,28,84,96,114,144,145,146,151,153,154,155,156,158,159,161,162,163,167,168,170,173,174,178,179,182,183,187],depict:[23,90],deploi:[4,96,167],deploy:[153,175],deprec:[6,90,153,154],depth:[28,84,165,167,171,172,173,186],depth_camera:171,depth_camera_control:171,deriv:[84,146,158,160,170,173],descent:[101,154],describ:[19,20,96,148,149,156,160,161,162,163,167,170,173,179,180,185,186,187,188],descriopt:108,descript:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,27,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,69,70,71,72,73,75,77,78,79,80,82,83,84,85,86,87,90,91,92,94,95,96,97,98,99,100,101,102,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,152,153,158,159,160,161,162,163,165,167,170,173,174,183,185],descriptor:172,design:[5,6,8,27,28,89,96,101,103,153,155,160,174,178,183,185,187,188],desir:[84,96,99,128,145,148,153,155,156,161,174,181,185],desired_linear_vel:[99,161],desired_linear_vel_:161,desk:150,destin:[27,28,61,149,170,171,173],destroi:145,destroynod:27,detail:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,20,28,87,96,103,108,111,114,145,148,152,153,154,155,158,160,161,162,163,167,168,169,170,172,174,179,185,186,188],detect:[4,28,52,56,83,84,89,90,99,145,156,168,170,171,177,181],detection2d:171,detection3d:171,detector:[28,89,181],detectron2:4,determin:[0,67,107,117,128,163,167,173,178,179,180],determinist:[11,28,94,101,175],dev:[144,147],devcontain:[145,146],devcontainerid:145,devel:[184,186],develop:[3,4,5,8,11,14,22,24,25,28,103,105,143,145,146,154,166,173,174,175,179,189],developercertif:148,dever:145,deviat:[85,96,106,156,174],devic:145,diademata:149,diagnost:170,diagnostic_msg:170,diagnosticarrai:170,diagon:109,diagram:[150,172,181],diamet:170,dictat:189,did:[20,21,158,161,162,171,173,179,180],didn:174,diego:14,diff:[90,103,165,174],diff_driv:170,diff_drive_control:170,diffdriv:96,differ:[10,18,19,20,22,23,24,25,28,60,83,84,88,99,100,103,105,108,111,114,145,146,148,150,152,154,155,160,163,167,169,170,171,172,173,174,175,176,179,181,183,185,188,189],differenti:[8,85,96,100,103,105,150,153,154,165,167,168,170,171,173,174,189],differentialmotionmodel:85,difficult:[28,100,154,174,189],difficulti:[1,2,3,4,5,6,7,8,9,10,11,12,13],digit:[101,128,165],dijkstra:[3,97,154,165,167],dilig:146,dime:174,dimens:[153,173,177],direct:[4,56,90,96,99,103,106,118,131,132,137,144,145,153,156,166,167,172,177,182,187],directli:[96,129,145,146,148,153,159,160,173,179,183,185],directori:[128,144,145,146,153,154,158,160,161,162,163,165,168,170,171,173,174,183,185],disabl:[83,84,85,91,130,131,132,154,155,177],disable_calib_cb_fast_check:177,disagre:85,disappear:84,discard:[109,154,178],discontinu:[101,103,132],discours:[0,148],discov:[144,159],discover:[158,160,161,162,163],discoveri:[94,145],discret:[28,145,148,167,170],discretize_by_tim:122,discuss:[3,6,20,28,148,152,153,154,161,162,167,168,169,170,171,172,173,175,189],dislpai:171,dispatch:28,displac:[31,44],displai:[2,98,131,153,168,170,171,173,174,178,185,188],disproportion:96,disscuss:153,dist:[131,132,177],dist_to_travel:[26,44],distanc:[18,20,21,27,28,31,44,54,55,56,59,61,77,85,86,90,96,99,100,117,122,131,132,137,151,152,153,161,165,167,170,171,172,174,181,189],distance_backward:56,distance_forward:56,distance_remain:[153,163],distancecontrol:[18,19,88,90,152],distancetravel:88,distancetraveledcondit:152,distant:56,distinct:[28,172],distort:[101,177,178],distortionk1:171,distortionk2:171,distortionk3:171,distortiont1:171,distortiont2:171,distribut:[96,143,145,146,148,149,157,166,183],distro:[143,144,149,170,171,173,177,182,184,186],distroa:143,distrob:143,dive:173,diverg:[131,132,174],divid:[152,153],do_beamskip:85,do_refin:[101,102,104,131,132,155,176],doc:[8,144,149,152],dock:[18,19,28,167],docker:[145,146],dockerfil:[144,145],document:[8,10,15,19,23,28,144,145,148,149,152,170,171,172,173,178,179,180,183,184,185],doe:[4,9,20,22,23,24,25,83,84,89,96,111,113,131,132,145,153,154,155,156,158,161,162,163,168,170,174,175,176,183,185,188],doesn:[74,130,153,154,158,174,183],doing:[27,107,111,148,163,179],doisi:165,domin:[112,116,156],don:[131,132,136,149,153,172,174,176,179,181,182,183,184],done:[13,19,20,28,84,145,151,152,153,160,161,162,163,166,167,171,179,180,188],dont:173,door:18,doubl:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,51,52,54,55,56,57,59,61,69,77,79,80,82,83,84,85,86,87,90,91,92,94,95,96,97,98,99,100,102,104,105,106,108,110,111,112,113,114,115,116,117,119,120,121,122,123,124,125,126,127,130,131,132,133,134,135,136,137,138,139,140,141,142,153,161,162],doubt:96,down:[27,28,94,96,99,105,114,149,152,154,155,174,175,179,185,187],download:[5,145,177],downsampl:[90,96,130,131,132,154],downsample_costmap:[130,131],downsample_factor:[130,131],downsampling_factor:[130,131],downstream:153,doxygen:147,dozen:28,drag:[149,188],dramat:[131,132,152],draw:[183,185],drawn:183,drift:[28,170],drivabl:[100,167,174,189],drive:[1,26,27,35,44,90,96,99,103,131,132,150,153,161,165,167,168,170,171,173,174,183],drive_on_head:[35,86],drive_on_heading_error_cod:44,driven:[4,174],driveonhead:[26,88,155],driver:[1,13,16,143,145,170,171,177],drivetrain:165,drivewhl_l:173,drivewhl_l_joint:170,drivewhl_r:173,drivewhl_r_joint:170,drop:[9,152,188],dropdown:2,dual:146,dub:154,dubin:[131,132,153,154,165,167],dubiou:154,due:[0,6,9,11,23,28,32,33,35,36,37,85,96,106,131,132,148,152,153,154,155,163,170,171,174,178,188,189],dumb:28,dummi:160,dump:167,duplic:[28,163],durabl:173,durat:[52,69,82,86,87,91,94,96,137,148,154,159,161,175,181],dure:[6,23,83,84,90,94,96,131,132,145,152,153,154,155,159,160,168,173,174,180,182,184,188],dwa:[3,17,165,167],dwb:[1,3,9,17,22,24,25,28,29,118,119,120,121,122,133,134,135,136,137,138,139,140,141,142,151,152,165,167,174,189],dwb_core:[91,93,152,153,167,189],dwb_critic:[93,117],dwb_local_plann:152,dwb_plugin:[93,117],dwblocalplann:[91,93,152,167,189],dynam:[0,3,13,15,18,22,24,25,28,78,79,83,84,96,131,132,150,151,152,153,158,159,160,161,162,163,166,167,171,173,174,185,186,187,188,190],dynamicfollowpath:152,each:[11,17,19,22,24,25,26,27,28,60,83,84,85,86,87,91,92,96,98,104,106,129,146,148,150,151,153,154,155,158,159,160,161,162,167,170,171,172,173,174,175,176,178,179,183,185,188],earli:[5,11,16],earlier:[85,131,132,146,149,154,158,172],easi:[10,11,14,19,28,145,146,148,169,171,184],easier:[148,167,171,172,173,174,179,189],easili:[13,19,28,87,145,152,153,154,156,174,180,187],ecosystem:[0,28,103,154,174],edg:[4,96,172,183],edit:[8,153,165,170,171,176],editor:[183,185,188],educ:14,effect:[2,4,84,90,113,130,145,152,154,170,183],effici:[23,28,103,171,174,175],effort:[8,14,28,106,148,150,153,167,171,174,186],efk:170,eight:178,eitan:165,either:[1,19,20,27,84,85,95,96,113,145,146,155,156,165,167,170,171,180,185,188],ekf:170,ekf_filter_nod:170,ekf_localization_nod:170,ekf_nod:170,elaps:153,elast:[3,151,167,189],element:[8,151,158,170,173],elev:[18,28,146,148],elif:[27,154],elimin:173,elong:90,eloqu:28,els:[27,83,92,153,154,160,161,163,170,187],elsewher:180,email:[0,14,28,148],emb:172,embed:[6,28,154,174,175],emerg:[6,9,84,89],emit:171,emploi:84,empti:[41,42,112,115,116,127,152,153,154,161,163,178],emul:145,emulate_tti:[183,185],enabl:[10,13,23,51,83,84,85,92,96,99,107,108,109,110,111,112,113,114,115,116,127,128,129,132,145,146,150,153,154,155,156,158,161,162,163,165,170,171,173,174,175,184,186,187,188],enabled_:160,enact:[9,79,189],encod:[28,108,114,170,172,183,185],encompass:174,encount:[16,167,171,179,180],encourag:[0,14,23,96,148,173,175,179],end:[6,11,21,28,83,84,96,97,101,130,154,156,158,160,161,162,163,165,173,174,175,178,179],endpoint:[131,132],energi:[96,171],enforc:[90,106,111,153,177],enforce_path_invers:[96,156],engag:148,engin:[6,144,146,151,180],enhanc:148,enough:[19,155,168,177],enrich:146,ensur:[4,9,11,13,21,22,24,25,28,94,96,99,145,146,148,151,153,154,155,167,168,172,173,174,175,180,186],enter:[22,24,25,28,96,158,161,162,163,183],entir:[12,19,20,22,24,25,144,145,148,165,167,174],entiti:170,entri:[14,170,176,179,180],entryfil:174,entrypoint:144,enumer:[30,31,41,42,44,45,52,54,188],env:145,environ:[4,5,9,10,12,28,103,143,144,145,146,148,149,150,167,168,170,171,172,174,182,183,187],environemnt:171,environment:[92,150],envok:[30,31,44,54],envrion:186,ephemer:145,eppstein:165,eqal:90,equal:[28,83,84,108,160,177,178,183,185],equat:105,equip:[171,188],eros:178,error:[28,30,31,41,42,44,45,47,48,52,54,58,71,72,73,83,84,85,87,143,152,153,154,165,168,171,176,178,182,186],error_cod:[58,71,72,73,175,176],error_code_id:[30,31,41,42,44,45,47,48,52,54,176],error_code_id_nam:[155,175],error_code_nam:[47,48,87],error_codes_to_check:58,especi:[85,131,132,146,151,154,172,176,182,184,186,189],essenc:172,essenti:[6,131,132,154,171,174],establish:175,estim:[15,84,85,101,106,149,151,153,160,161,162,163,170,171,172,182],estimated_time_remain:[153,163],etc:[4,10,13,18,27,28,83,84,87,108,145,146,148,153,155,158,163,167,169,170,172,174,184,188],eth:5,euclidean:[153,174],evalu:[117,120,132,167],evalul:7,even:[20,21,22,24,95,96,99,106,131,146,152,153,154,165,167,168,169,170,174,179,183],evenli:85,event:[1,13,148,154],eventu:[155,171,173],ever:[96,153],everi:[18,20,22,24,25,56,81,90,92,96,99,112,116,148,153,154,159,160],everyon:[146,148],everyth:[149,154,160,170],everywher:[96,151],exact:[96,101,130,131,132,145,155,167,168,174,181,183],exactli:[130,149,174,185],exampl:[1,7,15,16,17,18,19,20,23,28,103,144,145,146,152,153,154,156,158,159,160,161,162,163,168,169,170,171,172,173,174,175,176,177,178,179,180,183,185,186,188,189],example_assisted_teleop:27,example_follow_path:27,example_nav_through_pos:27,example_nav_to_pos:27,example_rout:27,example_waypoint_follow:27,exce:[30,31,44,54,114,153],exceed:[19,155],excel:[1,7,9,189],except:[27,28,39,83,91,148,153,155,162,165,170,179,185],exception:[163,170,180],excess:11,exchang:96,exclud:155,exclus:23,exe:179,exec:145,exec_depend:[170,173,175],execut:[10,11,17,19,21,22,24,25,27,75,79,87,100,107,145,146,148,152,153,154,159,160,163,165,167,168,170,171,172,173,175,178,179,180,183,185,188],executeprocess:[170,171],executor:[11,27,28,107,153,155],exemplari:18,exhaust:166,exhibit:23,exist:[4,8,11,12,17,28,83,84,95,96,130,143,145,148,152,153,154,156,161,163,174,180,181,188],exit:[22,24,28,94,152,154,179,180],expand:[97,131,132,133,145,154,167,173],expans:[8,97,105,131,132,153,154,155,165],expect:[5,11,27,85,96,98,112,116,148,150,152,153,163,170,175,176],expected_planner_frequ:[98,105],expected_update_r:[112,116,186],expend:174,expens:[28,116,154,155,170],experi:[1,2,3,4,5,6,7,9,10,12,26,144,145,146,150,154,173,179,182],experienc:169,expert:[4,14],expir:[23,68,165,186],explain:[11,19,20,23,146,148,168,179,180,184,189],explan:[19,89,103],explicitli:[4,27,146,183],explor:[171,172],exponenti:[85,96,110,165,171],expos:[20,28,104,153,155],exposur:7,express:[114,161,183,185],extend:[160,170],extens:[23,28,96,145,146,155],extent:99,extern:[4,22,24,25,27,83,91,94,127,144,145,151,152,155,156,175,190],extra:[90,131,132,154,183],extract:[154,163,165],extrem:[2,19,83,111,153,171],facilit:[146,154],factor:[79,90,96,110,130,131,141,171,174],factori:159,fail:[19,20,22,24,25,27,28,91,94,107,130,131,132,151,153,154,155,158,163,165,179],failed_to_make_progress:[71,155],failed_to_smooth_path:[73,155],failur:[1,18,19,20,21,22,24,25,28,30,31,44,54,58,60,61,62,64,65,66,67,68,70,71,72,73,74,75,81,96,150,151,153,154,159,165,175,179,181],failure_toler:91,fair:8,fairli:179,faith:148,fake:28,fall:84,fallback:[22,24,25],fals:[26,27,30,52,65,83,84,85,87,90,92,94,96,97,99,105,106,107,108,110,112,113,114,115,116,117,120,122,130,131,132,133,136,149,153,154,155,158,160,162,163,170,171,174,178,179,182,183,186,187,188],familiar:[19,28,173],fanci:145,far:[83,84,96,131,132,149,154,156,171,174,181,189],farm:186,fashion:20,fast:[83,84,85,101,102,131,132,154,178],faster:[154,174],fault:[12,27,28],favor:154,favourit:[183,185],feasibl:[28,96,100,102,103,111,150,153,154,156,165,167,174,189],featur:[1,4,6,8,9,14,28,85,99,102,145,148,149,153,154,165,166,173,183],feaur:183,feed:175,feedback:[14,27,28,87,106,148,154,163],feedback_msg:163,feel:[6,143,146,173,174],ferguson:[14,150],fetch:[161,162],fetullah:165,few:[4,11,14,20,27,79,90,144,145,167,171,174,179],field:[4,83,84,85,114,130,152,153,154,155,158,160,162,163,170,171,173,175,177,179,183,185,186],figur:188,file:[1,2,17,18,28,84,86,87,94,95,105,128,143,144,145,146,148,149,150,152,153,154,159,160,165,168,172,173,174,175,176,177,181,182,183,184,185,186,187,188],filenam:[170,171],filepath:[132,163,174],filesystem:[146,179],fill:[4,148,152,159,177,183,185,188],filter:[6,13,30,85,91,101,170,186,187,190],filter_dur:82,filter_info_top:[95,108,111,114,183,185],filter_mask:95,filter_mask_data:185,filter_mask_serv:[183,185],filter_space_valu:95,final_bt_statu:163,find:[14,28,56,87,96,99,106,131,132,145,146,148,149,150,152,153,155,156,161,163,167,173,174,176,178,179,180,181,182],find_if:161,find_packag:179,findchessboardcorn:177,finder:[153,171],findpackageshar:173,fine:[96,149,174,185],finish:[152,180],finit:[28,96,188],first:[20,28,74,75,83,96,115,144,145,148,150,154,155,156,161,165,166,168,170,171,172,173,174,175,176,178,179,181,182,183,184,185,186,188],first_map_onli:85,first_map_only_:85,firstli:23,fit:[96,174,187],fix:[99,113,148,152,155,166,168,170,171,172,173,177],flag:[9,145,170,173,177,179,180],flagship:14,fleet:28,flexibl:[14,87,96,158],flip:[108,153,155,167,173],flip_threshold:108,flood:19,flow:[1,19,20,22,24,25,75,76,148,159,188],fluidli:96,fly:[153,179,188],fn_tol:90,focal:177,focallength:171,focu:[12,19,27,173,187,188],focus:178,focuscamera:173,folder:[20,145,146,171,177],folk:[148,154,179],folllow:170,follow:[1,2,3,9,10,18,19,22,24,25,27,29,45,52,78,84,86,90,91,92,95,98,99,106,114,127,128,129,144,146,148,149,150,151,152,153,154,155,156,158,160,161,162,163,165,167,168,169,170,171,172,173,174,175,176,177,178,179,180,182,183,184,185,186,187,189,190],follow_path_error_cod:[45,71,87],follow_path_error_code_id:175,followpath:[18,19,20,21,22,23,24,25,27,28,34,43,46,88,91,93,96,99,100,152,155,159,161,163,167,181,189],followpathact:[43,46,53],followpathrecoveryfallback:[19,22,24,88],followwaypoint:[27,155],fonction:154,fondli:14,fool:174,footprint:[2,83,84,86,92,96,104,111,112,116,131,136,154,155,156,160,167,169,173,187],footprint_clearing_en:[92,112,116],footprint_pad:92,footprint_top:[84,101,102,104,158,176],footprintapproach:84,footprintcost:27,footprintcostatpos:27,forc:[85,96,156],forcefulli:145,forese:152,forget:182,forgot:148,fork:[28,93],forklift:23,form:[5,84,105,160,171,172],formal:[28,150,178],format:[10,83,84,90,96,128,145,153,170,171,173,183,185,188],former:[14,83,84],formerli:[91,155,165],formul:156,formula:185,fortun:170,forward:[0,9,19,28,56,90,95,99,100,117,122,132,137,140,141,145,149,156,159,172,174,189],forward_point_dist:[93,134,138],forward_prune_dist:[117,155],forward_sampling_dist:[100,189],found:[3,8,20,23,27,28,70,89,100,103,117,130,131,132,145,146,150,151,153,154,155,158,159,160,161,162,163,165,166,167,168,170,171,173,175,180,182,183,184,185,186],foundat:163,four:[19,28],foxi:[11,28,162],fraction:154,fragment:178,frame:[2,28,51,56,59,61,70,77,83,84,85,86,87,90,92,95,104,108,111,112,114,116,120,143,151,161,162,168,170,171,172,173,177,187],frame_id:[27,95,112,116,161,162,170,183,184,185],frame_nam:171,framework:[0,2,8,14,28,103,150,155,170,174,175],francisco:[150,165],free:[10,28,92,95,96,113,130,143,146,151,165,170,171,173,174,178,182,183],free_spac:178,free_thresh:[183,185],free_thresh_default:95,freeli:173,freespac:[22,24,25,174],frequenc:[19,20,83,86,91,92,96,98,106,131,132,170],frequent:[132,174],fresh:145,friction:2,friendli:[96,173],from:[2,5,6,7,8,9,11,12,17,19,20,21,22,23,24,25,27,28,43,46,49,51,53,56,60,83,84,85,86,87,89,90,91,92,95,96,99,100,101,105,106,107,112,114,116,130,131,132,134,137,138,142,143,144,145,146,147,148,149,150,151,152,153,154,156,158,159,160,161,162,163,165,166,167,168,170,171,172,173,174,175,176,177,178,181,182,183,184,185,186,187,188,189],from_imag:144,from_msg:154,from_numb:158,from_second:161,front:[83,84,134,138,161,173,174,187],front_cast:173,frustrat:154,fsm:28,full:[5,7,12,20,28,85,92,96,111,117,143,148,152,153,154,166,167,168,169,170,172,173,174,178,181,183,185,188,189],fulli:[28,85,131,132,148,149,153,154,167,174,176,186],fun:[0,16],fundament:[163,179],further:[11,20,23,96,102,131,132,145,148,154,172,179],furthest:96,fuse:[28,166,170],fusion:[15,28,170,172],futur:[1,4,8,11,22,28,83,84,85,108,111,114,152,154,181],gain:[8,96,99],galact:[85,87,158,160,162,171,186,188],game:28,gamma:96,gap:173,gather:[14,28],gaussian:[85,96,170,171],gazebo:[1,2,3,4,5,6,7,9,10,11,12,13,143,149,158,159,160,161,162,163,168,169,173,174,178,182,183,185,186],gazebo_model_path:149,gazebo_ro:[154,170],gazebo_ros_camera:171,gazebo_ros_pkg:170,gazebo_ros_ray_sensor:171,gazeborosimusensor:170,gdb:[145,179],gdb_test_nod:179,gdb_test_pkg:179,gdbtester:179,gear:153,gen:96,gener:[0,3,5,10,19,23,28,79,84,90,97,103,105,106,117,130,132,145,146,147,150,151,153,154,155,165,167,168,170,171,172,174,175,178,179,180,184],general_goal_check:153,generate_launch_descript:[170,171,173,183,185],generos:174,gentl:174,genuin:163,geograph:170,geometr:[173,174],geometri:[4,5,9,170,171,173],geometry_msg:[41,42,47,51,56,78,152,161,162,163,170,184],get:[1,4,10,19,20,27,28,68,87,91,96,101,105,112,116,131,135,144,145,147,150,152,153,154,155,158,159,160,161,162,163,165,166,169,170,172,173,175,176,177,178,180,181,182,183,185,186,187,189,190],get_clock:161,get_logg:[158,159,161,162],get_package_share_directori:[163,179,180,183,185],get_paramet:[160,161,162,163],get_shared_package_path:153,getandtrackrout:27,getblackboard:163,getcostidx:27,getcostmap:162,getcostmaptimestamp:27,getcostxi:27,getcurrentbtfilenam:163,getdefaultbtfilenam:163,getdefaultbtfilepath:163,getfeedback:[27,154],getglobalcostmap:27,getglobalframeid:[27,162],getindex:[27,160],getinput:159,getlocalcostmap:27,getnam:163,getorigini:27,getoriginx:27,getpath:27,getpaththroughpos:27,getresolut:27,getresourceinfo:155,getresult:[27,154],getrout:27,getsizeincellsi:27,getsizeincellsx:27,getsizeinmetersi:27,getsizeinmetersx:27,gettoler:153,ghcr:144,gif:23,gimp:183,gine:[99,150],git:[5,144,146,148,177,183,184,185,186],github:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,146,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],give:[11,96,148,149,150,152,158,159,166,167,170,171,172,173,174,175,179,185,189],given:[3,6,23,27,28,31,34,44,52,54,84,86,96,101,102,108,152,153,154,155,156,159,160,161,162,165,167,170,174,176,180,188],global:[19,22,23,24,25,27,50,60,62,66,79,85,86,88,90,99,115,120,138,139,151,152,154,155,156,160,161,162,165,168,170,171,172,173,174,178,182,183,185,186],global_costmap:[19,22,23,24,25,86,88,92,101,102,104,108,111,114,158,159,160,168,171,176,178,183,185,186],global_costmap_top:[86,158],global_footprint_top:[86,158],global_fram:[51,59,61,77,86,87,92,155,158,159,160,163,171],global_frame_:162,global_frame_id:85,global_path:162,global_plan_:161,global_plan_pos:161,global_plann:17,global_planner_plugin:162,globallyupdatedgo:88,globalplann:162,globalupdatedgo:[25,60],gmail:2,gnu:[179,186],goal:[11,18,19,20,21,22,24,25,27,28,34,41,42,45,47,48,51,55,60,61,62,67,78,79,87,88,90,91,97,98,99,117,123,124,125,126,130,131,132,134,135,141,142,149,151,152,158,159,161,162,163,170,173,174,175,176,181,184,185,187,189],goal_:159,goal_blackboard_id:[87,163],goal_blackboard_id_:163,goal_check:[46,91,93,99,100,153,161,189],goal_checker_id:[27,45,46],goal_checker_nam:117,goal_checker_plugin:[91,93,99,100,152,153,189],goal_checker_plugin_id:[124,126],goal_checker_selector:46,goal_distance_bia:117,goal_pos:[27,153,154,161,163,184],goal_reached_tol:61,goal_sub_:163,goal_upd:[78,181],goal_updater_top:78,goalalign:[93,117],goalaligncrit:93,goalanglecrit:96,goalcheck:[46,152,154,161],goalcheckerselector:[22,24,25,88,153],goalcomplet:163,goalcrit:96,goaldist:[93,117],goaldistcrit:93,goalreach:[20,77,80,82,88],goalreceiv:163,goals_blackboard_id:[87,163],goaltool:182,goalupd:[19,20,22,23,24,25,60,88,159],goalupdat:[21,88,181],goalupdatedcondit:152,goe:[9,20,23,114,154,158,161,162,163,176],going:[4,14,27,28,79,96,150,153,154,159,176,179,181,183,185],golai:[29,165],gone:19,good:[1,6,28,85,96,105,106,131,148,150,156,158,160,161,162,163,168,169,173,174,177,179],googl:148,gothroughpos:27,gotopos:[27,154],gpal:90,gpu:[4,145],grab:[90,146,163,170],grade:[28,150,170],gradient:[5,28,90,101,154,160],gradient_factor:160,gradient_index:160,gradient_lay:160,gradient_layer_1:160,gradient_layer_2:160,gradient_plugin:160,gradient_s:160,gradient_tol:90,gradual:90,grai:[173,185],grant:145,granular:[90,122],graph:[3,10,105,132,155,166,180],graphic:[8,146,183,185],grasp:171,great:[7,14,19,148,154,179],greater:[3,96,105,145,161,175],green:[90,166,177,182,188],grei:185,grep:143,grid:[6,7,28,92,95,112,116,120,165,167,168,171,173,184,186],grid_map:5,gridbas:[19,21,22,23,24,25,41,42,49,88,97,98,105,130,131,132,153,159,162,167,176,181],groot:[87,88,190],ground:[168,170,173],group:[11,13,14,28,80,109,148,155,165,178],group_connectivity_typ:[109,178],gtest:12,guarante:[100,106,131,150,167,172,189],gui:[2,146,149,170,173,177,188],guid:[18,19,20,144,146,152,154,155,156,160,162,166,167,168,170,171,172,173,175,186,187],guidelin:155,guillaum:165,gzclient:149,habit:174,hackbaselin:171,had:[12,14,154,155,171],haghighipanah:165,half:[19,99,131,132,171],hall:174,hallmark:6,halt:[19,20,23],hand:[28,96,100,106,154,156,168,172,173,174,189],handi:145,handl:[11,17,19,23,27,28,84,86,91,94,95,98,104,145,153,154,155,158,159,160,161,162,163,171,173,174,175,179],handler:156,hangout:148,hansen:14,happen:[14,19,148,161],happi:148,hard:[10,14,22,52,84,151,153,163,174],hardcod:[22,24,25,155,159,163],hardwar:[84,106,145,167,171,173,186,188],harsh:154,harshli:105,has:[2,3,4,6,8,11,12,14,17,19,20,22,23,24,25,27,51,59,60,62,68,69,83,86,88,89,90,96,99,113,123,124,125,126,130,131,132,143,145,146,148,149,150,152,153,154,155,156,158,159,160,161,163,165,168,170,171,172,173,174,179,180,182,183,185,187,188,189],has_paramet:163,have:[0,3,4,6,10,11,12,14,16,17,19,20,22,23,24,25,27,28,51,84,86,91,92,96,97,98,99,103,104,105,107,108,111,114,130,131,132,143,145,146,148,150,152,153,154,155,156,158,159,160,161,162,163,165,167,168,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],head:[35,44,96,99,100,130,132,148,154,165,169,170,172,174,181,189],header:[151,160,161,162,170,184],headless:[146,149,174,178,187],headlight:[108,155],hear:174,heart:[28,167],heavi:[84,90,131],heavili:174,height:[27,83,84,92,99,112,116,160,171,173],hello:158,help:[2,3,4,5,8,11,16,22,24,25,28,90,99,132,147,148,151,153,154,155,158,160,162,165,167,169,170,172,173,174,175,180,183,186,188,189],henc:[154,168,171,173,175],here:[0,3,14,20,22,23,24,28,74,75,76,77,78,79,80,81,82,83,84,96,100,145,146,148,149,151,152,153,154,155,156,159,160,161,162,163,165,170,173,175,176,177,179,182,184,188],heurist:[28,99,103,130,131,132,153,154,167],hfsm:28,hide:173,hierarch:[28,188],high:[2,3,4,5,6,8,28,84,96,99,102,105,106,116,130,131,132,148,150,151,153,167,170,178],higher:[4,6,9,12,19,28,84,90,92,96,106,108,131,132,150,153,154,155,163,174,175,181,183,185,188],highest:[28,155],highli:[17,28,90,96,103,140,149,150,156,165,167,172,174,176,182,184,186,189],highlight:[8,18,27,90,145,167,177,188],hint:174,histori:173,hit:[179,185],hold:[28,171,188],holder:[148,153],holonom:[90,91,96,99,142,150,165,174],home:[128,154,174,179,181],hood:[11,154],hooper:165,hope:154,hopefulli:[19,96],horizon:156,horizont:[109,171],horizontal_fov:171,horizontal_fov_angl:186,hospit:1,host:[17,28,86,91,95,98,104,107,145,146,151,158,167,180],hot:163,hotel:[183,185],hour:182,hous:108,how:[2,7,18,27,28,75,84,85,88,90,96,105,112,116,120,134,135,138,139,145,147,148,151,155,158,159,160,161,162,163,167,168,169,170,171,172,173,174,175,176,177,179,180,181,182,183,184,185,186,187,188,189],how_many_corn:105,howev:[4,6,9,14,21,22,24,25,28,83,84,96,101,145,149,152,153,154,158,163,168,170,173,174,176,179,183,185,186,187,189],hpp:[158,160,161,162,163],html:144,http:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],huerist:153,huge:96,human:[1,4,28,165],humbl:[83,84,85,86,91,93,96,99,100,149,158,187,188,189],hundr:[1,28],hurt:171,hybrid:[3,100,103,132,145,153,154,155,156,165,167,168,174,189],hypot:[161,162],hypothet:19,icon:188,idea:[17,149,150,154,173,174],ideal:[7,12,154,155,158,161,162],identifi:[4,7,11,13,145,153,160,167,180],idl:20,ieee:150,ifcondit:[170,173],ifunspecifi:170,ignit:166,ignor:[85,143,144,159,170,178],illustr:178,ilqr:3,imag:[16,23,28,90,101,128,132,151,153,173,176,177,178,183,185],image_format:128,image_pipelin:177,image_raw:[128,171,177],imagin:[19,28,158,165],immedi:[22,24,84,94,153,158,163,170,173,179],immin:[84,150],impact:[22,24,96,174,179],impass:183,impl:128,implement:[3,5,6,7,10,17,21,22,24,25,28,30,31,41,42,44,45,47,48,54,57,75,85,86,87,91,92,94,95,96,97,98,99,103,104,105,106,107,146,148,151,153,154,155,158,161,162,163,165,167,168,170,171,174,175,176,184,186,188],implementaion:165,impli:128,implicit:27,implicitli:154,improv:[1,7,9,11,12,26,28,90,101,103,131,132,145,149,151,152,153,155,156,166,180],imu0:170,imu0_config:170,imu:[28,170,171,172],imu_joint:170,imu_link:170,imu_plugin:170,imu_sensor:170,inact:[28,96,158,161,162,163,173,175],incentiv:[96,156],includ:[4,6,7,10,13,14,19,27,28,75,87,88,103,108,122,144,145,146,147,148,150,151,152,153,158,159,160,161,162,163,165,167,170,171,172,173,179,180,181,183,184,185,186,189],include_last_point:122,inclus:[145,156,171,179],incom:[84,89,108,111,114,152,183,185],incompat:145,incomplet:166,inconsist:153,incorpor:[85,145,153],incorrect:[153,165],incorrectli:153,increas:[12,28,90,96,105,154,155,172,174,175,177],increasingli:28,incred:18,increment:[30,83,84,86,131,154],increment_recovery_count:159,indefinit:[19,20,27,148,181],independ:[14,28,86,114,150,153,155,159,171,187],index:[27,128,144,158,160,161,162,163,165,188],indic:[52,83,84,85,108,111,114,127,148,152,153,159,160,171,185],individu:[11,17,28,89,103,148,151,154,155,174,184],indoor:108,induc:[155,165,190],industri:[14,28,84,99,153,165,167,183],inerti:[171,173],inertia:[170,171,173],inf_is_valid:[92,112,116,186],infeas:[102,165],infer:173,infin:56,infinit:[21,91,112,116,131,132],inflat:[28,85,92,111,113,133,165,171,178,183,186],inflate_around_unknown:[92,110],inflate_con:113,inflate_unknown:[92,110],inflation_lay:[92,108,109,111,114,160,168,171,178,183,185],inflation_radiu:[92,96,110,171],inflationlay:[92,171],influenc:96,info:[10,90,93,108,111,114,146,153,160,170,177],inform:[1,2,4,10,20,21,28,83,84,89,95,96,99,100,103,106,108,111,112,114,116,117,130,131,132,144,148,151,152,154,155,156,158,159,160,161,162,163,165,170,171,172,173,174,175,176,178,179,180,182,183,184,185,186,187,188],infrar:171,infux:154,ing:20,inher:[145,146],inherit:[153,159,160,161,162,163],init:[27,154],init_pos:27,initalorientationasrefer:170,initi:[8,27,63,70,85,96,102,143,145,146,149,152,154,155,158,160,161,162,163,165,173,174,181,183,187],initial_cov_:85,initial_orientation_as_refer:170,initial_pos:[27,63,85,154],initial_pose_:85,initializegoalpos:163,initialposereceiv:[20,88],inject:179,injuri:9,inlin:[160,162,186],inner:[11,187],inorm:160,inout_port:188,inproceed:150,input:[6,20,27,28,84,87,90,96,101,102,112,113,116,127,150,153,155,158,159,160,161,162,165,170,173,176,179,181,187,188],input_at_waypoint:127,input_go:[21,22,51,78,181],input_path:[21,55,56,181],input_port:188,input_sensor_typ:[113,171],input_top:127,inputatwaypoint:[107,153,165],inputport:159,inquiri:14,inscrib:[154,174],inscribed_inflated_obstacl:178,insert:[159,171,179],insid:[28,84,89,90,91,93,103,107,145,146,154,155,160,170,171,175,179,180,183,186,187],insight:[11,154,166,174],inspect:[27,145],instabl:154,instal:[143,145,146,147,158,160,161,162,163,168,170,171,172,173,176,177,178,179,180,182,183,184,185,187,189],instanc:[28,84,128,149,156,159,167,170,175,183,185],instantan:[91,155],instanti:[167,173,175],instead:[13,19,22,24,25,78,83,85,96,102,117,144,145,151,152,153,154,155,156,158,163,170,171,172,174,175,176,179,181,182,183,187],instruct:[28,107,149,158,160,161,162,163,170,171,179,180,184],instrument:96,int16:175,integ:183,integr:[0,1,7,12,17,18,29,56,84,99,146,153,154,169,170,171,172,175,179,188],intel:[4,14,96,154],intel_realsense_r200_depth:[83,84,92,186],intellig:[150,174],intellisens:145,intend:[87,149,152],intent:[23,96,174],intention:[14,90,183],interact:[28,87,88,96,150,153,154,173,175,176,179,190],intercorrel:178,interest:[7,10,11,14,18,27,28,145,148,163,172,174,176,179,180,181,182,184,188],interfac:[3,5,13,17,20,28,84,87,104,145,146,150,151,152,155,158,159,160,163,165,171,176,182,186],interfer:[92,183],interior:177,intermediari:[22,150,153],intern:[19,22,24,25,100,150,155,160,163,170,175,189],interoper:171,interpol:[99,106,183],interpolation_resolut:162,interpolation_resolution_:162,interpret:[92,95,172,178],interprocess:145,intersect:99,interti:173,interv:[83,84],interven:1,intial_pos:20,intrest:179,introduc:[28,83,99,146,148,151,153,154,169,171,173,175,178],introduct:[18,88,173],intuit:[174,189],inturn:23,invalid:[18,27,145,155,163],invers:[96,156,183],inversion_xy_toler:96,inversion_yaw_toler:96,invert:[25,96,153],investig:179,invilad_start:175,invok:[30,31,41,42,44,45,47,48,52,54,57,144,145,175,180],involv:[4,5,6,11,19,21,96,99,147,153,155,156,168,175],ipc:145,iro:150,iron:[87,95,163],irregular:151,is_recoveri:[26,30,54],is_voltag:65,isbatterycharg:[88,155],isbatterylow:[19,20,88],isbatterylowcondit:152,ish:14,isn:[96,148,179],isol:[146,180],ispathvalid:[25,88],isstuck:88,issu:[0,2,3,5,6,8,14,22,24,25,27,28,96,148,152,153,154,166,167,172,174,178,179,183,185,186],istaskcomplet:[27,154],item:[2,11,19,27,28,166],iter:[22,24,25,27,28,51,84,87,90,93,96,102,106,130,131,132,155,160],iteration_count:96,its:[1,6,8,9,11,12,19,20,22,23,24,25,27,28,77,80,81,82,84,90,92,96,97,100,102,103,105,130,131,132,144,148,151,152,153,154,155,158,160,161,162,163,165,167,168,170,171,172,173,174,175,176,177,178,179,180,183,185,186,187,188,189],itself:[28,114,131,132,145,154,159,163,171,176,183,185,188],ixi:[171,173],ixx:[171,173],ixz:[171,173],iyi:[171,173],iyz:[171,173],izz:[171,173],jag:102,jaggedli:96,jerk:185,jerki:[96,106],jeronimo:165,jetbrain:146,jetson:4,jitter:96,job:[28,96],join:[148,168,170,171,173,183,185],joint:[170,171,173],joint_state_publish:[170,173],joint_state_publisher_gui:[170,173],joint_state_publisher_gui_nod:[170,173],joint_state_publisher_nod:[170,173],jonatan:150,joshua:[14,165],joshuawallac:14,journal:150,jpeg:153,jpg:153,json:[2,145,146],jump:170,june:103,junior:148,just:[8,21,22,24,25,28,79,92,96,137,146,148,154,159,160,168,170,171,172,173,179,180,183],juzhenatpku:2,kalman:170,kcachegrind:180,keep:[14,19,28,84,96,145,152,153,156,159,161,162,165,170,172,173,183,188],keep_goal_orient:90,keep_start_orient:90,keepout:[92,95,153,165,185,190],keepout_filt:[92,111,178,183],keepout_filter_mask:183,keepout_mask:183,keepout_param:183,keepoutfilt:[92,111,153,183],keeprunninguntilfailur:[21,181],kei:[20,85,145,148,149,163,175,178],kept:[14,109],kernel:178,key_nam:188,key_name2:188,kick:[28,158],kidnap:50,kill:179,kind:[23,170,179],kinemat:[2,93,100,102,103,150,153,165,167,170,173,174,189],kinodynam:3,know:[11,14,28,99,103,143,148,152,153,159,160,165,172,173,185,188],knowledg:[4,7,11,148,179,186],known:[19,23,27,28,85,99,154,163,165,174,177,186],konolig:165,kurt:165,label:145,laid:[183,185],lambda:159,lambda_short:85,land:8,landmark:170,lane:[28,95,111,153,165,183],languag:176,larg:[20,28,84,96,99,131,132,152,166,170,173,174,177],larger:[28,79,94,96,99,101,130,148,153,165,179,187],largest:[167,168],laser:[6,9,83,84,85,112,116,165,171,172,187],laser_likelihood_max_dist:85,laser_link:173,laser_max_rang:85,laser_min_rang:85,laser_model_typ:85,laserscan:[84,92,112,116,155,184],last:[6,14,20,22,24,55,56,85,90,97,103,105,106,122,130,131,132,134,135,138,139,145,154,163,167,168,170,172,173,175,183,185],lastli:[148,155,167,168,170,171,172,173],latenc:[17,106,151,152],later:[5,96,131,132,145,146,148,154,158,159,160,161,162,163,171,180,186,188],latest:[83,84,144,145,189],latter:176,lattic:[3,100,103,131,154,155,165,166,167,174,189],lattice_filepath:132,launch:[17,28,86,94,95,146,149,158,160,161,162,163,167,168,172,175,177,178,181,183,185,187,188],launch_ro:[170,173,179,183,185],launchconfigur:[170,173,183,185],launchdescript:[170,173,183,185],layer:[2,4,7,10,11,92,108,111,113,114,130,131,133,145,150,151,153,154,160,171,174,183,186],layeredcostmap:160,lazi:153,ld_preload:186,lead:[14,96,99,128,148,153,154,185],leader:14,leadership:14,lean:144,learn:[4,7,11,19,28,88,146,150,158,159,162,171,172,173],least:[21,84,145,148,153,170,187],leav:[96,99,152,179,187],led:[83,155,156],left:[6,28,41,42,99,105,115,131,132,145,149,154,161,162,168,170,171,173,177,178,180,182,185,188],left_joint:170,left_wheel_est_vel:170,leg:[103,146,150,165,167,174],legaci:117,length:[79,90,92,96,105,131,132,154,171,173,174,175,177],length_factor:[23,79],less:[9,61,84,96,98,99,109,151,154,170,178,183,189],let:[11,19,20,28,127,129,143,146,153,154,158,159,162,170,171,172,173,174,181,185,187],lethal:[92,96,110,165,171],lethal_cost_threshold:92,lethal_obstacl:[160,178],level:[5,9,17,19,22,24,25,28,84,89,102,148,150,153,154,155,175,180,183,185,188],leverag:[7,11,27,144,146,154,174,176,181],lib:[179,186],libgazebo_ros_camera:171,libgazebo_ros_diff_dr:170,libgazebo_ros_factori:[154,170,171],libgazebo_ros_imu_sensor:170,libgazebo_ros_init:[154,170,171],libgazebo_ros_ray_sensor:171,libjemalloc:186,libjmalloc:186,librari:[5,6,7,10,15,17,27,28,87,151,152,154,158,160,161,162,163,171,172,176,179,186,188],libstdc:179,licens:[1,2,3,4,5,6,7,8,9,10,11,12,13,147],lidar:[6,9,28,168,170,171,178,186],lidar_joint:171,lidar_link:[171,172],life:188,lifecycl:[17,27,29,106,143,150,152,153,163,167,169,174,180,183,185],lifecycle_manag:[94,175,183,185],lifecycle_manager_costmap_filt:[183,185],lifecycle_manager_navig:175,lifecycle_nod:[175,183,185],lifecyclemanag:154,lifecyclemanagercli:154,lifecyclenod:[28,154,161,163,179],lifecycleshutdown:27,lifecyclestartup:27,lifecyl:175,light:[108,154,177,183,185],lightli:96,like:[2,4,8,13,14,18,19,20,21,22,24,25,27,28,87,95,96,103,107,130,145,146,148,149,150,153,154,158,159,160,163,165,168,169,171,172,173,174,175,176,179,180,181,183,184,185,186,188,189],likelihood:85,likelihood_field:85,likelihood_field_prob:85,limit:[8,28,84,91,95,96,106,114,130,131,132,145,153,161,165,167,170,174,181,190],limitedaccelgener:93,line:[12,27,101,130,152,155,158,160,161,162,163,167,168,170,171,172,173,174,176,179,180,187],linear:[31,44,84,90,95,99,122,153,155,161,170,183],linear_acceler:170,linear_granular:[93,122],linear_limit:[84,155],linear_solver_typ:90,linear_vel:161,linearli:[28,114,153,183,185],linecost:27,link:[1,2,3,4,5,6,7,8,9,10,11,12,13,16,20,105,148,154,170,171,172,173],links1:173,lint:148,linter:145,linux:[145,146,179,186],list:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,20,22,27,47,48,51,83,84,86,87,89,91,92,93,94,98,103,104,107,117,145,146,148,150,151,152,153,155,159,160,161,163,165,166,167,170,171,174,175,177,178,179,183,185,188,189],listen:[20,83,84,86,143,152],lit:177,littl:[174,179],live:[4,28,146,153,158,172,174,182,184,188],lld:144,load:[28,45,86,91,92,95,96,98,104,107,117,145,150,151,152,153,154,158,159,160,161,162,163,165,167,171,173,176,180,183,185,186,188],loadabl:[92,152,153,186],loadbehaviortre:163,loadlibrari:186,loadmap:85,local:[1,3,9,10,11,19,22,24,25,27,43,46,49,53,85,86,94,96,99,106,117,120,124,145,146,148,149,150,152,153,154,155,160,161,162,163,165,167,168,172,174,178,183,185,186,187],local_costmap:[19,22,23,24,25,38,39,40,84,86,88,92,109,111,158,159,160,168,171,178,183,185],local_costmap_top:[86,158],local_footprint_top:[86,158],local_fram:[86,155],local_or_glob:153,local_plann:17,localization_lifecycle_manag:152,locat:[9,23,27,28,131,132,141,149,158,160,161,162,163,167,170,171,173],lock:[13,161,163],lockfil:145,locu:14,log:[146,148,154,158,159,170,171,179],logger:154,logger_:[161,163],logic:[9,18,19,22,24,25,28,155,159,163,175,188],logininteractiveshel:145,logo:8,longer:[8,17,23,79,130,154,155,158,179],look:[0,2,11,19,51,86,99,134,138,141,148,149,150,152,159,167,170,171,172,173,174,175,180,183,185,186,187,188,189],lookahead:[99,153,161,189],lookahead_dist:[99,161],lookahead_dist_:161,lookahead_tim:[93,99,141],looker:[174,189],lookup:[56,154],lookup_table_s:[131,132],loop:[20,28,83,96,99,106,154,162,163],loop_rat:[107,153],loss:84,lot:[170,173,179],loung:150,low:[5,17,19,20,65,96,101,106,151,165],lower:[14,19,65,84,86,96,108,154,155,171,175],lowest:[47,48,96,153,155,175],luckili:[172,179,188],luggag:181,macenski2020marathon2:150,macenski2023regul:150,macenski2023survei:150,macenski:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,99,150,165],machin:[4,17,28,145,146,170,171,172,175,188],macro:[131,132,158,159,160,161,162,163,173],made:[6,8,28,84,91,92,94,123,125,145,146,148,154,155,160,163,167,168,173,174,178,181,183,185,187],mai:[0,3,4,5,6,10,14,22,24,25,27,28,79,83,84,96,99,101,103,111,131,132,137,144,145,148,150,152,153,154,155,156,159,160,163,166,167,168,170,171,172,173,174,175,176,178,179,180,181,182,183,185,188,189],main:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],main_tree_to_execut:[18,19,20,21,22,23,24,25,26,88,159,181],mainli:[19,171,172,173],mainstai:[28,103],maintain:[0,8,14,15,17,145,148,150,154,155,163,165,166,171,174,175],maintre:[18,19,20,21,22,23,24,25,26,88,159,181],major:[10,13,28,103,150,153,158,163,166,168,173,179],make:[1,2,7,9,10,11,12,13,14,17,20,22,24,25,26,28,55,56,91,96,99,100,105,112,114,116,142,143,145,146,148,152,153,154,155,156,158,161,162,163,165,167,168,170,171,172,173,174,175,177,178,179,180,181,182,183,184,185,186,187,189],make_shar:163,make_uniqu:159,malfunct:83,malici:146,manag:[27,28,29,145,149,150,152,153,167,169,170,172,173,174,175,177,180],mandatori:[153,158,159,161,162,185],maneuv:[96,131,132,152,168],mani:[11,17,18,19,22,24,25,28,75,84,85,150,151,152,160,165,171,172,174,176,179,180,181,183,185,188,189],manipul:[10,27,173],manner:[28,150],manual:[0,56,94,144,145,149,170,175,180],manufactur:171,map:[27,28,29,41,42,45,51,59,61,77,85,86,87,91,92,98,108,111,112,114,115,116,130,131,132,143,149,150,151,153,156,159,160,161,162,163,165,167,168,170,172,174,178,182,183,185,187,188,190],map_filepath:27,map_fram:170,map_io:152,map_load:152,map_sav:[95,152],map_save_dur:186,map_saver_cli:[152,184],map_serv:[17,85,92,95,152,183,185],map_subscribe_transient_loc:[92,115,171],map_top:[85,92,115,171],mapped_name_of_plugin:[161,162],mapper_params_online_sync:179,mapping_mod:186,mapsav:154,mapserv:152,maptoworld:27,marathon:150,march:28,marder:165,margin:[96,132],mark:[4,28,90,92,112,113,116,136,155,163,171,178,183,185,186,188],mark_threshold:[92,113,116,171,186],marker:[96,120,148,171,173],marker_lifetim:120,market:11,martin:[99,150],mask:[28,95,108,111,114,153,155,165,178],mask_top:[95,183,185],mask_valu:[95,108,114],mask_yaml_fil:[183,185],mass:[171,173,185],massiv:[158,171,178],master:[112,116,160,166,171],master_arrai:160,master_grid:[112,116,160],match:[6,58,71,72,73,85,86,87,96,104,131,132,150,155,159,161,168,174,175,187],matchsiz:160,matej:165,materi:173,matrix:[28,170],matt:14,matur:[24,25],max:[90,96,99,112,113,116,130,131,132,156,161,171],max_accel:106,max_allowed_time_to_collis:99,max_allowed_time_to_collision_up_to_carrot:99,max_angl:171,max_angle_to_furthest:96,max_angular_accel:[99,100,189],max_angular_vel:161,max_angular_vel_:161,max_beam:85,max_decel:106,max_dur:27,max_height:[83,84],max_i:160,max_it:102,max_iter:[90,130,131,132],max_j:160,max_linear_accel:154,max_linear_decel:154,max_lookahead_dist:99,max_obstacle_height:[92,112,116,171,186],max_on_approach_iter:[130,131,132],max_particl:85,max_path_occupancy_ratio:96,max_planning_tim:[130,131,132,153],max_planning_time_m:153,max_point:[83,84,155,187],max_rat:82,max_robot_pose_search_dist:[56,96,99],max_rotational_vel:[86,158],max_scaling_factor:117,max_smoothing_dur:52,max_spe:[82,96],max_speed_xi:[93,119],max_vel_i:[93,119],max_vel_theta:[93,119],max_vel_x:[93,119,152],max_veloc:106,max_wheel_acceler:170,max_wheel_torqu:170,max_z:186,maxim:[90,96,174],maximum:[2,28,52,56,82,83,84,85,86,90,91,92,95,96,99,100,102,106,112,114,116,119,123,125,130,131,132,153,154,155,161,165,171,178,183,185],maxwithoutunknownoverwrit:[112,116,156],mayb:2,mcl:6,mean:[0,1,19,20,28,84,96,106,114,131,145,146,152,155,170,171,172,174,178,183,185],meaning:[154,163,175],meant:[83,84,105,154,155,169,174],meantim:13,measur:[9,26,91,96,112,116,131,132,153,155,165,170,171,172,173,178],mechan:[5,11,84,160,179],medium:[1,7,8,9,11,12,13,166],meet:[96,124,141,148],member:[4,148,158,161,162,163],memori:[28,145,154,174,175,179,186],mention:[151,152,153,167,185,189],mentor:[0,1,2,3,4,5,6,7,8,9,10,11,12,13],menu:188,mere:145,merg:[5,13,145,148,152,160],merit:146,merzlyakov:[14,150,165],mesh:[28,173],messag:[11,27,28,30,31,41,42,43,44,46,49,53,54,83,84,85,86,89,91,92,98,112,114,116,145,148,153,155,156,158,159,161,163,170,175,183,185,187],message_success:158,messsag:148,met:[126,141,148,153,189],meta:[183,185],metadata:[28,145,163,183,185,188],metapackag:[5,17],meter:[18,26,27,28,85,92,97,100,130,131,132,177,178,189],method:[3,4,6,18,22,24,25,27,28,94,96,112,116,134,135,138,139,148,153,154,155,158,159,160,161,162,163,179,180,188],metric:[89,103,155,159],michael:165,micro:174,mid:28,middl:[101,167,174,185,188],middlewar:28,might:[28,85,96,106,153,156,163,168,170,171,179,180,183,185,188],migrat:[8,166],miguel:165,mike:14,millisecond:[87,129,153],mimic:173,min:[113,161,166,171],min_angl:171,min_approach_linear_veloc:99,min_batteri:65,min_dist_to_obstacl:96,min_height:[83,84],min_i:160,min_j:160,min_lookahead_dist:99,min_obstacle_height:[92,112,116,171,186],min_particl:85,min_point:[83,84,155,187],min_rat:82,min_rotational_vel:[86,158],min_spe:82,min_speed_theta:[93,119],min_speed_xi:[93,119],min_theta_velocity_threshold:[91,93,99,100,189],min_turning_r:96,min_vel_i:[93,119],min_vel_x:[93,119],min_veloc:106,min_x_velocity_threshold:[91,93,99,100,189],min_y_velocity_threshold:[91,93,99,100,189],min_z:186,mind:[96,145,170,172],minim:[2,11,96,149,154,155,163,167,170,174],minima:96,minimal_group_s:[109,178],minimum:[2,9,28,65,82,83,84,85,86,90,92,95,96,99,106,109,112,116,119,123,125,131,132,137,140,153,154,155,165,167,171,172],minimum_turning_radiu:[90,131],minor:[124,171],minut:[28,177],mirror:[96,132],misalign:178,misloc:178,miss:[13,153,173,174,180,188],mission:158,mittal:165,mixin:[144,145],mixtur:85,mkdir:[144,183,185],mkhansen:14,mmethod:159,mnimum:123,mobil:[1,4,5,7,9,10,12,14,27,28,150,170,171,172],modal:170,mode:[21,84,96,106,145,155,156,183,185,188],model:[4,17,28,29,83,84,85,90,103,131,145,149,150,152,153,165,167,170,171,173,174,182,186,187],model_dt:96,model_typ:186,modelplugin:170,moder:174,modern:[103,150,174],modest:96,modif:[28,145,148,153,154],modifi:[6,18,55,56,87,88,93,101,145,148,153,154,156,158,159,161,162,163,165,167,168,170,173,179,180,181,188],modu:189,modul:[30,31,41,42,44,45,47,48,54,57,87,94,107,156,160],modular:[6,146,150,165],mohammad:165,moment:155,monitor:[23,29,83,150,153,156,188,190],monitorandfollowpath:23,monocular:177,monolith:17,mont:[6,28,85,171],month:148,moor:[15,150],more:[2,3,4,6,7,9,10,11,12,14,17,18,19,24,25,28,56,83,84,85,90,93,96,99,100,106,108,111,114,130,131,132,140,144,145,146,148,150,152,153,154,156,158,159,160,161,162,163,165,167,168,169,170,171,172,173,174,175,177,178,179,180,181,182,183,184,185,186,187,188,189],moreov:178,most:[9,19,22,24,25,84,85,96,100,103,149,154,159,165,170,171,172,174,176,179,180,189],mostli:171,mothership:158,motion:[3,4,28,85,90,131,132,140,141,153,156,165,167,170,172,188],motion_model:96,motion_model_for_search:131,motiv:[10,154],motor:[106,150],mount:[145,146,172],move:[14,19,23,28,79,83,84,96,108,123,125,127,132,137,140,150,151,152,153,154,155,162,165,166,172,173,174,177,181,182,183,184],move_bas:17,movecamera:173,moveit:[8,14],movement:[83,84,85,90,106,132,155,187],movement_time_allow:[91,93,99,100,123,125,155,189],mpc:[3,96,155,165,167],mppi:[155,165,166,174],mppicontrol:96,msg:[27,41,42,47,51,79,84,108,154,161,162,163,165,170],much:[28,90,99,106,148,150,152,153,155,172,173,174,183],multi:[7,10,11,28,153,154,165,167],multi_tb3_simulation_launch:156,multipl:[6,11,17,22,24,25,28,43,46,49,53,79,84,86,103,104,146,150,152,153,156,161,162,167,170,171,172,173,174,175,176,179,185],multipli:[95,108,114,130,131,183,185],multithread:0,multitud:[28,171],must:[4,14,20,27,28,59,85,92,95,99,102,106,109,112,116,123,125,131,132,133,148,152,154,155,158,159,161,162,163,165,167,170,171,172,175,176,177,180,182,184,186,188],my_camera:177,my_contain:175,my_mark:171,my_nav_through_poses_bt:[87,163],my_nav_to_pose_bt:[87,156,163],my_packag:[87,156,163],my_world:171,myawesomenewnod:188,myplugin:[160,162,186],naiv:[103,130],name:[8,14,15,18,19,20,21,22,23,24,25,26,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,53,54,57,83,84,85,86,87,88,89,91,92,94,97,98,104,105,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,144,145,148,152,153,154,160,165,166,167,168,170,171,172,173,174,175,176,177,179,180,181,183,185,186,187,188,189],name_:[160,162],name_of_paramet:[161,162],namespac:[28,86,87,91,92,93,96,98,104,107,112,116,117,152,155,156,160,161,162,167,170,171,174,175,183,185,186,189],narrow:[96,145],narrowest:96,nasti:[103,154],nativ:[145,155],natur:[28,96,156,163,174],nav2:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,19,21,22,23,24,25,26,27,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,144,145,146,147,148,149,151,152,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,172,173,176,177,184,186,188,189,190],nav2_amcl:[17,85,171,184],nav2_back_up_action_bt_nod:[87,159],nav2_behavior:[30,31,44,54,57,86,154,158],nav2_behavior_tre:[20,28,88,152,153,159,163,188],nav2_bringup:[149,152,153,154,155,158,160,161,162,163,168,171,174,178,179,180,181,182,183,184,185,187],nav2_bt_navig:[17,18,19,87,152,153,163,181,188],nav2_bt_waypoint_follow:28,nav2_ceres_costaware_smooth:[104,176],nav2_clear_costmap_service_bt_nod:87,nav2_collision_monitor:[89,187],nav2_common:[183,185],nav2_compute_path_to_pose_action_bt_nod:87,nav2_constrained_smooth:[90,154],nav2_control:[17,91,93,99,100,123,124,125,126,151,153,155,180,187,189],nav2_cor:[17,87,151,153,155,158,161,162,163],nav2_costmap_2d:[17,92,108,109,111,114,152,153,154,155,160,161,168,178,183,185],nav2_costmap_2d_mark:171,nav2_costmap_filters_demo:[183,185],nav2_default_view:182,nav2_depend_w:143,nav2_distance_controller_bt_nod:87,nav2_distance_traveled_condition_bt_nod:87,nav2_dwb_control:17,nav2_follow_path_action_bt_nod:87,nav2_gazebo_spawn:154,nav2_goal_reached_condition_bt_nod:87,nav2_goal_updated_condition_bt_nod:87,nav2_gradient_costmap_plugin:160,nav2_gradient_costmap_plugin_cor:160,nav2_hfsm_navig:28,nav2_initial_pose_received_condition_bt_nod:87,nav2_is_stuck_condition_bt_nod:87,nav2_lifecycle_manag:[17,175,183,185],nav2_map_serv:[17,183,184,185],nav2_mppi_control:96,nav2_msg:[27,28,91,152,153,159,183,185],nav2_multirobot_param_al:156,nav2_multirobot_params_:156,nav2_navfn_plann:[17,97,98,162,167],nav2_param:[153,154,155,158,160,161,162,163,168,174,175,176,178,180,183,185,186],nav2_pipeline_sequence_bt_nod:87,nav2_plann:[17,41,42,151],nav2_pure_pursuit_control:161,nav2_rate_controller_bt_nod:87,nav2_recoveri:[151,154],nav2_recovery_node_bt_nod:87,nav2_regulated_pure_pursuit_control:[99,100,153],nav2_reinitialize_global_localization_service_bt_nod:87,nav2_rotation_shim_control:[100,154,189],nav2_round_robin_node_bt_nod:87,nav2_route_serv:175,nav2_rviz_plugin:17,nav2_sensor_driv:175,nav2_simple_command:[27,154],nav2_simple_navig:17,nav2_simulation_launch:149,nav2_single_trigger_bt_nod:87,nav2_smac_plann:[90,103,130,131,132,153],nav2_smooth:[90,101,102,104,176],nav2_sms_bahavior:158,nav2_sms_behavior:158,nav2_sms_behavior_plugin:158,nav2_speed_controller_bt_nod:87,nav2_spin_action_bt_nod:87,nav2_straightline_plann:162,nav2_straightline_planner_plugin:162,nav2_system_test:17,nav2_test_util:181,nav2_theta_star_plann:[105,153],nav2_time_expired_condition_bt_nod:87,nav2_transform_available_condition_bt_nod:87,nav2_tree_nod:188,nav2_util:[28,152,154,162,163],nav2_velocity_smooth:[106,154],nav2_w:[144,145,179],nav2_wait_action_bt_nod:[87,159],nav2_waypoint_follow:[17,28,107,127,128,129,151,153,155],nav2_world_model:151,nav:[14,27,153,154],nav_cor:17,nav_msg:[27,41,42,55,56,79,161,162,163,170,175],navfn:[3,17,29,96,100,101,103,151,165,167,168,174,176,189],navfnplann:[97,98,162,167],navig:[0,1,2,3,5,6,10,13,14,15,16,18,21,27,29,59,60,61,62,77,80,82,88,96,103,107,145,148,150,151,153,158,159,161,164,166,168,169,170,171,172,173,174,175,176,180,181,186,188,189,190],navigate_through_pos:[87,163],navigate_through_poses_error_cod:[47,87],navigate_through_poses_w_replanning_and_recoveri:[47,48],navigate_to_pos:[87,163],navigate_to_pose_error_cod:[48,87],navigate_to_pose_w_replanning_and_recoveri:[19,163],navigate_to_pose_w_replanning_goal_patience_and_recoveri:154,navigate_w_replanning_and_recoveri:[153,159,188],navigate_w_replanning_and_round_robin_recoveri:153,navigaterecoveri:[19,22,23,24,25,88,159],navigatethroughpos:[87,88,163],navigatethroughposesnavig:[87,163,165],navigatetopos:[28,87,88,107,152,159,163,181],navigatetoposeact:28,navigatetoposenavig:[87,163,165],navigatewithreplan:[18,19,21,22,23,24,25,88,159,181],navigation2:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,145,147,148,149,150,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,173,174,175,176,177,178,179,180,181,182,183,185,187,188,189,190],navigation2_behavior_tre:17,navigation2_dynam:15,navigation2_tutori:[15,160,168,170,173,183,185],navigation_dur:27,navigation_launch:[154,168,171,180,184,187],navigation_lifecycle_manag:152,navigation_tim:[154,163],navigation_tutori:[158,161,162],navigatior:155,navigaton2:149,navigator_plugin:163,navigatorbas:163,navsat_transform_nod:170,navthroughpos:[154,165],navtopos:154,ncancel:163,ndt:6,near_goal_dist:96,nearbi:[83,84,99,153,178],nearest:[96,99,183],nearli:[154,174],neccessari:[158,161,162,163,172],necess:[160,161,163],necessari:[11,23,27,96,99,131,132,145,153,155,158,160,163,168,170,171,172,173,174,175,178,180,185,189],necessarili:20,need:[2,4,11,13,22,23,24,25,27,28,43,46,49,53,79,84,86,90,91,92,96,98,99,104,107,144,145,146,148,150,153,154,155,158,159,160,161,162,163,167,168,170,171,172,173,174,175,176,177,179,180,181,182,183,185,187,188],need_recalculation_:160,neg:[106,131,132,153,159,170],negat:183,neglig:154,negoti:92,neigh:105,neighbor:[109,178],neighborhood:[96,165,167],neither:28,nest:[145,146,179],network:[11,28,145,151,154,159],neutral:186,never:[19,28,96,131,132,154,183,185],nevertheless:170,newer:[145,158,171],newest:[21,174],newli:[79,100,153,154,168,171,174,175,183,188,189],next:[4,5,19,20,22,23,24,25,28,96,106,107,127,129,145,149,151,152,158,160,161,162,163,165,167,168,170,171,172,173,178,185,188],next_target:188,nice:[28,158],no_inform:[112,116,178],no_readings_timeout:113,no_valid_control:[71,72,155],no_valid_rout:175,node:[0,17,18,19,21,22,23,24,25,27,29,43,46,49,51,53,55,56,58,59,60,63,69,71,72,73,75,76,77,78,79,80,81,82,87,90,94,103,105,106,128,131,132,143,145,151,152,158,159,161,162,163,166,167,169,170,172,173,174,177,181,182,183,184,185,187],node_:[154,158,159,160,161,162],node_nam:[94,175,179,183,185],nodebuild:159,nodeconfigur:159,nodeid:27,nodestatu:154,nois:[85,96,101,109,152,155,165,170,171,190],noisi:[153,170,178],nolint:163,nomenclatur:28,nomin:[22,24,25],non:[7,10,27,91,94,96,100,103,108,111,114,130,131,132,145,150,154,156,159,163,165,167,168,172,173,174,179,180,183,189],non_straight_penalti:[131,132],none:[27,43,46,47,48,49,53,83,155,163,174,175],nor:[96,180],normal:[145,154,179],notabl:146,note:[2,17,18,20,21,22,23,24,27,28,85,86,90,91,92,94,95,98,99,104,106,107,111,114,132,148,150,154,158,159,160,161,162,163,170,171,172,173,174,175,176,178,179,180,182,183,185,186,187,188,189],noteworthi:96,noth:153,notic:[96,160,170,171,173,179,188],notif:146,notifi:[94,159,163],notion:175,novel:[153,154],novelti:6,now:[11,19,20,22,23,84,149,151,152,153,154,155,156,158,159,160,161,162,163,168,170,171,172,173,174,176,179,180,181,182,186,188],nudg:165,num_attempt:23,num_coeff:177,num_cycl:26,number:[3,11,27,75,83,84,85,90,92,96,101,102,109,116,118,130,131,132,151,152,153,154,155,156,158,159,162,165,170,171,172,173,174,177,178,179,185,188],number_of_recoveri:163,number_of_retri:[19,20,22,23,24,25,75,88,159],number_recoveri:163,numer:155,numeric_limit:153,nutshel:28,nvidia:4,nxm:177,object:[5,10,11,27,28,78,96,150,153,154,155,156,158,160,163,169,171,173,174,186,190],observ:[112,116,146,158,161,162,163,170,171,172,189],observation_persist:[112,116,186],observation_sourc:[83,84,92,112,116,171,186,187],obsolet:153,obstacl:[0,1,3,9,15,18,21,28,66,79,83,84,85,90,92,99,109,110,116,130,131,132,133,136,150,151,154,155,165,167,168,171,172,173,181,182,186,187,190],obstacle_clearance_tim:154,obstacle_lay:[92,108,111,114,153,160,171,178,183,185,186],obstacle_max_rang:[92,112,116,153,171],obstacle_min_rang:[92,112,116,153,171],obstacle_rang:186,obstaclefootprint:117,obstaclefootprintcrit:93,obstaclelay:[92,171],obstacles_angl:[83,84],obstaclescrit:96,obstruct:177,obtain:[7,28,29,84,152,155,170,171,177],obvious:[151,174],occasion:[28,103],occdist_scal:117,occgridload:152,occup:[6,92,95,111,112,116,165,171,184],occupancygrid:[95,114,152,155,183,185],occupi:[21,28,92,95,96,112,113,116,155,171,183],occupied_thresh:[183,185],occupied_thresh_default:95,occur:[28,101,160,187],odd:101,odom0:170,odom0_config:170,odom:[28,70,83,84,85,86,87,91,92,106,143,158,159,168,170,171,172,184,187],odom_dur:106,odom_fram:170,odom_frame_id:[83,84,85,187],odom_r:[83,84],odom_smooth:163,odom_smoother_:163,odom_top:[87,91,106,159],odometr:[26,28],odometri:[15,18,83,84,85,87,91,106,120,163,169,171,172],odometry_fram:170,odomsmooth:163,off:[21,96,100,106,108,148,154,155,156,158,173,179,189],offer:[28,167,186,188],offic:1,offici:[15,144,149,168,170,171,172,173],offlin:154,offset:[172,173,175],offset_from_furthest:96,ofodom_fram:170,often:[20,28,90,154,170],old:[79,117,155,163,165],older:[91,93,99,100,149,189],omit:145,omni:[85,96,103,153,165,174,187],omnidirect:[85,96,100,103,154,165,167,170,174,189],omnimotionmodel:85,ompl:3,on_abort:159,on_activ:[28,158,161,162,163],on_cancel:159,on_cleanup:[158,161,162,163],on_complet:154,on_configur:[28,158,161,162,163],on_deactiv:[158,161,162,163],on_parameter_event_callback:154,on_success:159,on_tick:159,on_wait_for_result:[154,159],on_xyz:163,onactioncomplet:158,onc:[13,19,20,23,70,81,84,85,94,96,100,130,131,132,144,145,146,148,149,152,153,154,156,163,171,172,173,179,180,182,187,189],oncleanup:158,onconfigur:158,oncreatecommand:145,oncycleupd:158,one:[3,5,7,8,11,14,19,27,28,74,78,84,90,94,96,101,132,145,146,152,153,154,156,159,160,163,167,170,171,172,173,174,175,177,178,179,180,181,182,183,185,187,188,189],ones:[18,131,132,154,167,171],onfootprintchang:160,ongo:27,ongoalposereceiv:163,oniniti:160,onli:[0,3,9,11,19,20,21,28,41,42,51,75,81,83,84,85,89,90,92,96,102,111,131,132,141,145,150,151,152,153,155,156,158,159,160,162,165,166,168,169,170,171,172,173,174,176,178,179,180,183,184,188,189],onlin:[27,154],online_async_launch:[171,184],onloop:163,onpreempt:163,onrun:158,onto:[19,22,24,96,100,154,163,165,170,172,189],open:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,131,132,143,145,146,148,160,168,170,171,172,173,174,177,179,180,181,182,183,184,185,186,188],open_loop:106,opencl:7,openmp:7,openvdb:186,oper:[4,5,22,24,25,28,84,90,96,99,106,108,146,149,150,153,154,155,158,160,161,162,163,167,170,171,172,174,175,177,187,188],operandi:189,opinion:174,opportun:[22,24,25,156,159,163],oppos:[28,132],opposit:[94,132,156,172,183],opt:[144,149,170,173,182,184],optim:[3,18,23,28,90,96,103,111,130,145,153,154,155,165,167,168,174,175,177,189],optimi:174,option:[2,3,6,9,41,42,83,84,85,90,96,131,146,153,154,155,160,171,173,176,177,178,179,180,181,186,188],options1:173,orang:188,orbit:173,orchestr:[17,150,179,188],order:[1,11,28,92,94,96,107,114,151,153,154,159,160,161,163,168,170,171,173,174,175,176,177,183,185,188],ordinari:92,org:[15,148,152,173,174],organ:[14,144,145,161,162,188],organiz:23,orient:[55,56,90,96,97,99,101,105,124,130,131,132,141,149,156,160,162,167,170,171,182,183,184,185],orientaton:154,origin:[2,5,6,8,14,27,55,56,78,84,90,92,130,131,132,147,152,153,168,170,171,173,176,183,185],origin_i:92,origin_x:92,origin_z:[92,116,171,186],oscil:[93,101,102,137],oscillation_reset_angl:137,oscillation_reset_dist:137,oscillation_reset_tim:137,oscillationcrit:93,ost:177,other:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,19,20,23,59,61,84,96,99,101,106,111,145,146,148,149,150,153,154,155,156,158,159,161,162,163,165,167,168,169,170,171,172,173,175,176,177,178,179,180,181,183,185,186,188,189],otherwis:[4,20,58,61,64,65,66,67,68,71,72,73,85,96,101,113,132,153,154,165,170,174,175,185],our:[0,11,14,16,28,95,132,145,146,148,154,158,159,160,161,162,163,167,170,171,172,173,175,178,179,180,181,183,185,186,187,188],ourselv:172,out:[0,1,9,13,14,20,21,22,27,28,79,84,87,88,96,101,106,130,131,132,145,148,152,153,154,155,158,161,162,163,165,170,171,172,174,179,180,183,187,188,189],outcom:96,outdat:90,outdoor:108,outermost:[83,84],outlin:[19,21,153,168,172],output:[1,2,3,4,5,6,7,8,9,10,11,12,13,28,84,96,130,131,132,150,153,154,159,160,167,170,171,172,173,175,176,179,180,183,185,187,188],output_go:[21,22,51,78,181],output_path:[21,55,56,181],output_port:188,output_typ:171,outsid:[84,100,154,155,181,189],over:[5,6,8,11,14,19,21,27,28,51,82,84,96,133,148,150,153,154,155,163,167,170,171,174,175,177,183,186,187,189],overal:[7,19,74,167,171],overcam:154,overcom:96,overhead:11,overlai:[145,146],overlaid:28,overlay_mixin:144,overli:96,overrid:[92,95,117,145,154,158,159,160,161,162,163],overridden:[86,91,92,95,98,152,153,159,160],overriden:155,overrod:84,overshoot:[96,99,153],overview:[103,146,170,172],overwhelm:19,overwrit:[95,112,116],overwritten:[87,112,116,154],owen:165,own:[11,18,28,84,85,103,145,148,150,151,152,153,158,159,160,161,162,163,165,167,170,171,172,173,174,175,180,183,184,185,187],ownership:148,pablo:165,packag:[5,8,17,18,27,28,83,84,88,89,92,96,99,100,103,106,132,143,144,145,148,149,153,154,155,158,159,160,161,162,163,169,170,171,172,173,174,175,176,177,178,179,180,181,183,185,187,189],pad:92,padmanabhan:165,page:[0,2,3,8,28,89,91,103,108,111,114,153,155,176,178,183,185],pai:174,pain:[172,179],pair:[19,20,96,102,114,153,156,174,177,183,185,189],palett:[145,146,188],pan:154,pancak:188,pane:[173,185],panel:[2,103,173,188],paper:[99,150,161],par:174,parabol:105,parallel:[7,13,187],param:[28,100,153,160,170,173,174,179,180,183,185,187],param_rewrit:[183,185],param_substitut:[183,185],param_tol:90,paramet:[2,13,19,20,26,28,29,47,48,65,77,80,82,93,145,151,152,158,159,160,161,162,163,167,168,170,171,173,174,175,176,177,178,179,180,182,183,185,187,188,189],parameter:[154,186,188],parameter_ev:170,parameterev:[154,170],parameteriz:188,parametervalu:[160,161,162],paramlog:154,params_fil:[158,161,162,163,168,174,183,185],paremet:155,parent:[19,20,70,145,153,158,160,161,162,170,171,172,173,179],parent_nod:163,parma:162,pars:[2,28,145],parser:177,part:[28,32,33,35,36,37,55,56,84,85,103,111,148,152,154,160,167,168,171,173,176],partial:154,particip:[11,148],particl:[6,7,28,85,149,165,174,178],particlecloud:152,particular:[6,20,23,28,83,96,152,154,163,176,179,180],particularli:[28,101,145,171,183],pass:[21,22,24,25,43,46,49,51,69,92,94,96,100,117,133,144,154,165,180,181,183,189],passabl:153,passag:[131,132],passibl:183,passthrough:146,past:[14,168,170,171,173,186],patch:[146,148],path:[3,4,18,19,20,21,22,23,24,27,28,29,41,42,45,47,48,52,55,56,66,68,77,79,87,88,90,91,95,97,98,99,100,101,102,103,104,105,117,128,130,131,132,133,138,139,143,144,145,150,152,153,158,159,160,161,162,163,165,167,168,170,171,173,174,176,178,179,180,181,182,183,185,188,189],path_blackboard_id:[87,163],path_blackboard_id_:163,path_distance_bia:117,path_downsampling_factor:90,path_loc:56,path_resolut:96,path_upsampling_factor:90,pathalign:[93,117],pathaligncrit:[93,96],pathanglecrit:96,pathdist:[93,117],pathdistcrit:93,pathexpiringtim:[25,88,154],pathfind:168,pathfollowcrit:96,pathlongeronapproach:[23,88,165],patienc:155,patience_exceed:[71,155],patrol:[27,28],pattern:[19,20,177],paus:[18,129,149,151,153,154,155],payload:185,pdf:171,penal:[96,156],penalis:105,penalti:[96,131,132,140,154,174],pencil:183,pend:[28,163],peopl:[4,9,22,24,25,84,169],pepper:[155,178],per:[83,84,96,148,160,161,162,165,166,167,168,180],perceiv:[28,171],percent:[114,183,185],percentag:[65,85,113,114,161,165,180,183],percept:[10,28,150,165,169,171,177,186],perf:145,perfectli:[96,189],perform:[1,3,4,7,9,11,18,23,27,29,31,44,54,83,84,85,89,90,96,103,107,131,132,145,150,153,154,155,158,159,160,161,162,168,171,174,175,178,179,181,188],perhap:188,period:[19,88,90,145,151,154,160,163,165],permiss:28,permit:[4,148,183],perpetu:174,persist:[145,165],person:[21,23,27,145,148,181],perspect:84,perturb:[96,174],pf_err:85,pf_z:85,pgm:[183,185],phase:[3,6,132],phi:113,phone:158,photo:[128,153,165],photoatwaypoint:[107,153,165],physic:[100,169,170,171,174,179,180,184,186,189,190],pick:[5,27,28,107,182],pictur:[27,28,107,160,183,185,187],pid:[145,180],piec:172,pipe:[20,155],pipelin:[165,177],pipelinesequ:[18,19,21,22,23,24,25,88,159,181],pitch:[170,174],pivot:174,pixel:[28,92,178,183],pkg:[87,154,156,163,170,173,179,180,182],pkg_share:[170,171,173],pkg_share_dir:163,place:[13,27,28,54,92,99,100,112,116,130,132,148,153,154,155,156,158,160,161,162,163,165,167,173,176,177,178,183,185,187,189],placehold:163,plai:[28,168],plan:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],planar:[170,171],plane:[154,170,173],planned_footprint:131,planner:[1,2,4,9,10,17,18,19,20,22,23,24,25,29,41,42,49,72,84,89,90,92,96,99,100,101,102,106,111,120,138,139,150,151,152,158,160,164,166,168,169,175,176,181,183,186,189],planner_id:[19,21,22,23,24,25,27,41,42,49,88,159,176,181],planner_plugin:[97,98,105,130,131,132,152,167],planner_selector:49,planner_serv:[94,97,98,105,130,131,132,153,162,167,175],plannerselector:[22,24,25,88,153],plannerserv:154,plate:158,platform:[7,96,103,150,153,169,172,174,188,189],pleas:[0,2,3,14,20,27,28,84,91,99,108,111,114,148,150,152,158,160,165,167,168,171,172,174,176,178,179,182,183,184,185,186,187,188],plot:182,plu:[170,171],plugin:[1,5,11,12,13,17,18,20,27,28,41,42,45,52,85,87,90,96,97,99,100,101,102,104,105,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,149,150,166,168,169,173,175,178,180,181,183,185,187,188,189,190],plugin_id:[161,162,163],plugin_lib_nam:[87,159],plugin_nam:[160,162,186],plugin_name_:161,plugin_specific_paramet:[161,162,163],plugin_typ:[160,162,186],pluginlib:[3,28,151,158,160,161,162,163,176,186],pluginlib_export_class:[158,160,161,162,163],pluginlib_export_plugin_description_fil:[158,160,161,162,163],pluse:153,png:[128,153,183,185],pocket:96,point:[4,9,10,14,18,19,20,22,23,24,25,27,28,51,83,84,90,92,96,97,99,100,101,102,105,107,108,111,117,130,131,132,134,136,138,148,150,152,153,154,155,156,160,161,162,163,165,168,170,171,172,173,174,175,177,179,182,186,187,188,189],pointcloud2:[84,92,112,116,186,187],pointcloud:[83,84,92,155,171,186],pointcloudcutoff:171,pointcloudcutoffmax:171,pointcost:27,pointer:[153,154,158,159,160,161,162],polici:[96,171,173],poll:27,polygon:[27,89,155,156,168,187],polygon_front:83,polygon_limit:84,polygon_nam:[83,84],polygon_pub_top:[83,84,187],polygon_slowdown:[84,187],polygon_stop:[84,187],polygon_sub_top:[83,84],polygonfront:83,polygonlimit:84,polygonslow:[84,187],polygonstop:[84,187],pool:96,poor:28,pop:179,popul:[7,85,87,153,154,158,163,171,175,176],popular:[28,174,179],port:[17,20,87,148,152,153,154,159,171,176,181,188],portion:[19,91,176],portslist:159,pose2d:85,pose:[18,20,21,27,28,41,42,47,55,56,61,63,78,85,90,96,97,99,105,122,124,126,130,131,132,134,135,143,149,150,151,152,153,154,160,161,162,163,165,170,171,173,174,181,184,187],posearrai:152,poseprogresscheck:[91,165],posestamp:[27,41,42,47,48,51,56,78,153,154,161,162,163,175,184],posewithcovari:170,posewithcovariancestamp:170,posit:[1,4,56,83,84,91,124,149,151,153,154,159,160,161,162,163,170,171,172,173,174,178,181,182,184],possibl:[2,14,17,28,86,96,99,145,150,153,154,155,161,163,167,168,174,178,179,183,185,187],post:[0,14,83,84,85,108,111,114,131,132,148,176],postcreatecommand:145,potenti:[0,1,6,7,9,10,28,84,89,99,130,131,132,150,153,154,155,165,171,178,179,180],power:[4,19,90,96,146,154,174],power_supply_statu:64,power_supply_status_charg:64,pr2441:154,pr2454:154,pr2456:154,pr2459:154,pr2469:154,pr2479:154,pr2480:154,pr2483:154,pr2489:154,pr2993:154,practic:[145,148,153,158,160,161,162,163,172,174,183,187],pradheep:165,pre:[10,61,86,87,88,95,96,99,132,145,165,182,183,189],prebuild:145,precis:[28,153,168],precise_goal_check:[45,46,153],precompil:145,precomput:154,predefin:28,predict:[29,84,153,156,165],prediction_horizon_:96,predomin:148,preeemption:163,preempt:[19,21,27,152,159,163,165],preemption:[22,24,159,163],preemptiv:[145,156],prefer:[0,28,95,100,106,111,131,132,145,146,149,153,154,156,165,173,174,180,183,189],preferenti:96,preferforwardcrit:[93,96],preferr:173,prefix:[158,160,161,162,163,173,179,180,182],prepar:[170,173,175],prerequisit:[23,147,171],presenc:[4,96,174,183],present:[23,106,112,116,145,152,154,155,156,160,161,163,165,171,174,187],preset:187,press:177,presum:94,pretti:[171,172,174],prevent:[9,19,28,30,84,85,89,90,96,99,106,112,116,131,132,137,142,145,153,154,155,156,165,174,175,178,183],preview:2,previou:[20,25,96,148,153,155,156,160,163,165,168,170,171,173,174,185,186],previous:[13,153,154,155,156,161,163,171,179,180],primari:[1,6,19,100,101,154,171,173,175],primarili:[19,154,168,174],primary_control:[100,189],prime:174,primit:[26,28,131,132,154,173],princip:[160,177,185],principl:183,print:[27,90,154,179],printenv:143,prior:[20,79,85,151,154],priorit:154,prioriti:[83,84,148,155,163,175],privat:14,privileg:[145,146],probabalist:165,probabilist:152,probabl:[21,95,113,155,171,176],probe:[20,145],problem:[23,50,94,154,162,163,165,174,179],problemat:[90,99,179],proccess:179,proce:[163,173],proceed:95,process:[5,7,8,11,23,27,28,29,52,85,87,91,92,96,98,99,101,131,132,144,145,147,149,152,153,155,158,159,163,165,169,173,174,175,178,179,180,186,188,189],processor:[7,96,174],produc:[4,28,83,84,96,154,155,158,162,167,171,174],product:[9,28,134,135,138,139,145,146,150],profession:[22,24,25,150],profil:[1,2,3,4,5,6,7,8,9,10,11,12,13,96,179,190],program:[2,17,27,28,103,131,132,145,154,179,180,181],progress:[4,67,91,96,99,123,125,145,148,155,166,174,189],progress_check:[91,93,99,100,189],progress_checker_id:155,progress_checker_plugin:[91,93,99,100,152,189],progress_checker_plugin_id:[123,125],progresscheck:152,project:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,18,28,83,84,86,96,99,122,144,145,146,148,150,154,160,166,168,170,171,172,173,175,178,183,185,187,188,189],project_nam:[170,171,173],projection_tim:86,promis:154,promot:20,prompt:[2,146,179],prone:28,proof:28,proper:[90,172,173],properli:[9,27,133,154,168,169,170,171,172,173,178,183,185],properti:[20,84,145,170,171],propig:175,proport:[20,96,131,132,183,186],proportion:[106,161],propos:[0,6,152,153,154],proprtion:96,protect:148,provenli:28,provid:[2,4,7,11,17,18,19,20,22,24,25,27,28,29,43,46,49,53,58,84,85,87,88,92,95,96,101,106,112,116,138,139,144,145,146,148,149,150,154,155,158,159,160,161,162,163,166,167,169,170,171,172,173,174,175,176,178,179,181,182,184,188],providedbasicport:159,providedport:159,prox_len:[23,79],proxim:[23,51,79,96,99,153,154,187],prudent:146,prune:[96,117,145,156],prune_dist:[96,117,155],prune_plan:117,psutil:154,pub:184,publish:[21,43,46,49,53,83,84,85,87,91,92,93,95,96,106,108,111,114,116,117,127,131,149,151,152,153,154,156,158,161,163,165,168,170,171,174,176,177,181,182,184,187],publish_acceler:170,publish_cost_grid_pc:120,publish_evalu:120,publish_frequ:[92,171],publish_global_plan:120,publish_local_plan:120,publish_odom:170,publish_odom_tf:170,publish_tf:170,publish_trajectori:120,publish_transformed_plan:120,publish_voxel_map:[92,116,171,186],publish_wheel_tf:170,published_footprint:[84,86,101,102,104,158,168,176],publishfeedback:163,pull:[14,144,145,146,148,152,153,154,165,174,179,188],pure:[29,96,150,153,154,155,158,160,162,163,165,167,174,189],pure_pursuit_controller_plugin:161,purepursuitcontrol:161,purpl:90,purpos:[10,28,83,148,150,155,159,163,167,173,181,184,185],pursuit:[29,150,153,154,165,167,174,189],push:[90,145,148,166],push_back:162,put:[11,90,154,160,165,173,175,187],pycostmap2d:27,python3:[2,12,13,27,150,153,154,155],python:[4,10,150,153,170,183,185],qualifi:85,qualiti:[3,8,26,28,90,96,102,103,131,132,148,150,154,170],quaternion:[153,170,172],queri:[153,154,165,167],question:[0,148],queue:148,quick:[19,131,132,172,183],quickli:[7,145,148,154,172,188],quirk:[154,174,189],quit:[20,146,154,179],r8g8b8:171,race:145,rad:[86,91,96,99,100,119,123,124,126,137,141,189],radar:[28,170,171,186],radar_msg:171,radial:177,radian:[54,83,84,85,96,99,100,189],radii:[96,99],radiu:[22,51,83,84,90,92,96,99,110,123,125,131,132,133,154,165,167,168,171,173],ragged:28,rai:[7,171],rais:179,random:[85,155],randomli:[96,174],rang:[4,7,65,83,84,85,92,99,112,114,116,145,152,153,165,166,173,175,178,179,183,185,187],ranger:171,rangesensorlay:152,rare:[152,154],raster:[183,185],rate:[9,12,19,20,77,80,82,83,84,85,106,107,112,116,151,153,158,165,173,181],ratecontrol:[19,21,22,23,24,25,88,159,181],rather:[17,20,22,24,25,28,85,90,92,145,151,152,153,154,156,163,165,172,174,179,184],ratio:[131,132,173,177],raw:[86,104,150,176,179,183,185],raycast:[112,116,165],raytrac:[112,116,153,171],raytrace_max_rang:[92,112,116,153,171],raytrace_min_rang:[92,112,116,153,171],raytrace_rang:153,rcl_interfac:[154,170],rclcpp:[11,160,161,162,163],rclcpp_action:163,rclcpp_compon:175,rclcpp_error:[162,163],rclcpp_info:[158,162,163],rclcpp_lifecycl:[161,163],rclcpp_node:154,rclcpp_node_:154,rclcpp_warn:[159,163],rclpy:[27,154],reach:[0,14,19,20,23,91,96,124,126,129,130,160,161,165],react:[154,173],reaction:19,reactiv:[22,24,181],reactivefallback:[19,20,22,23,24,25,88,159],reactivesequ:[22,23,25],read:[6,8,19,28,83,84,113,146,153,154,165,171,179,183,185],readabl:173,reader:[169,189],readi:[23,144,145,148,149,154,160,173,174,179,183,185,187],readili:144,readm:[17,83,84,89,96,99,100,103,105,106,152,153,154,155,174],real:[4,9,12,28,84,148,170,171,172,173,177,181],realist:12,realiti:28,realli:[28,90,174,183],rearrang:17,reason:[6,28,83,84,96,130,131,132,148,154,160,163,168,172,174,179,187],reattempt:[22,24,25],rebuild:179,rebuilt:145,recal:[20,171],recalcul:160,receiv:[19,20,27,28,43,46,49,53,78,91,100,103,106,113,115,152,154,155,158,161,163,165,170,171,172,174,181,189],recent:[9,51,149,174],recharg:[19,28],reckon:28,recogn:178,recomend:154,recommend:[1,2,3,4,5,6,7,9,10,12,28,83,84,94,96,99,101,102,145,148,149,161,167,168,170,171,172,173,174,176,182,184,186,188,189],recompil:[160,179],recomput:19,reconfigur:[13,18,153,154,167,175],reconnect:94,record:148,recov:[19,85,94],recoveri:[2,18,22,23,24,25,30,31,54,57,75,86,87,88,150,151,152,155,158,159,163,165,176],recoveries_serv:[154,158],recovery_alpha_fast:85,recovery_alpha_slow:85,recovery_count:163,recovery_plugin:[152,154,158],recovery_serv:154,recoveryact:[19,22,23,24,25,88,159],recoveryfallback:[19,22,23,24,25,88,159],recoverynod:[19,20,22,23,24,25,88,159],recreat:145,rectangular:[90,168],rectifi:28,recurs:[101,102,131,132],red:176,redd:131,redesign:14,redistribut:148,reduc:[0,28,96,99,101,102,106,132,145,148,151,152,153,155,175],reduct:152,redund:152,reed:[90,131,132,153,154,165,167],reeds_shepp:131,reedshepp:154,ref:[1,2,3,4,5,6,7,8,9,10,11,12,13],refactor:[148,151],refer:[3,19,28,51,59,61,77,84,86,87,91,92,99,101,103,108,111,114,144,145,146,151,152,154,155,158,159,160,161,162,163,167,168,169,170,171,172,173,178,181,183,185,187,188],referenc:[160,170,171,187],refin:[28,90,102,131,132,149,154],refinement_num:[101,102,131,132,155],reflect:[145,153,156,171,173],refus:96,regard:[0,20,154,163,173,174],regardless:[83,84,106,146,160,170,180],regim:[96,174],region:[39,83,96,150,165],regist:[28,88,158,159,160,161,162,163,171,186],registerbuild:159,registr:186,registri:[144,145],regul:[29,150,153,154,161,165,167,174,189],regular:[28,30],regularli:167,regulated_linear_scaling_min_radiu:99,regulated_linear_scaling_min_spe:99,regulatedpurepursuitcontrol:[99,100],rehash:155,reimplement:[5,6],reinit:165,reiniti:165,reinitialize_global_loc:50,reinitializegloballoc:88,reject:[131,132,154,163],rel:[8,28,56,83,84,92,96,106,152,156,167,168,170,172,174,180],relat:[4,11,13,14,26,28,84,89,108,109,111,114,144,145,150,153,154,169,172,173],relationship:[96,172],relav:158,relax:145,releas:[27,151,152,166,186],relev:[1,2,3,4,5,6,7,8,9,10,11,12,13,19,150,151,159,163],reli:179,reliabl:[6,12,17,43,46,49,53,146,150,171,173],reloc:50,relwithdebinfo:180,remain:[13,19,20,21,28,90,96,120,145,146,151,152,153,154,158,159,160,161,162,178,189],remaind:28,remap:[32,33,34,35,36,37,41,42,45,153,154,170,171,175,176,179,180,181,187],rememb:[14,99,143,145,172,173],remot:[145,146,158,159,179],remote_containers_ipc:145,remote_containers_socket:145,remov:[11,21,22,51,55,56,95,101,109,112,116,145,151,152,165,170,171,176,178,179,180,186,188,189],removepassedgo:[22,88,153],renam:[86,145,152,153,154],renavig:19,render:146,reopen:146,rep145:170,rep:[28,150,153,166,170,172],repeat:[26,96,144,160,172,173],repeatedli:[183,185],repetit:[155,173],replac:[4,5,10,11,17,87,90,151,154,155,156,158,160,162,163,174,176,178,184,186,187],replan:[18,20,21,22,24,51,77,82,88,117,131,132,152,153,174,181],replic:145,repo:[12,28,105,144,146,181,186],report:[12,85,96,148,153,155,159,171],repositori:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,99,144,145,146,150,158,160,161,162,166,168,170,171,173,174,183,185,186],repres:[10,12,19,28,96,99,150,153,161,166,170,171,173,179],represent:[10,92,150,167,171,172],reproduc:[144,145],repuls:96,repulsion_weight:96,reput:8,request:[11,14,19,21,27,28,86,87,91,95,96,97,98,100,104,130,131,132,145,146,148,152,153,154,155,156,158,159,163,165,174,175,176,179,184,185,188,189],requir:[1,2,3,4,5,6,7,8,9,10,11,12,13,21,28,85,90,94,96,100,105,106,114,145,148,153,154,155,156,167,170,171,172,173,174,175,179,181,186,189],required_movement_angl:[123,155],required_movement_radiu:[91,93,99,100,123,125,189],rerun:145,resampl:85,resample_interv:85,research:[9,14,28],resembl:20,reserv:[22,24,25,155,175],reset:[68,85,96,137,149,152,153,154,159,160,163,165],reset_dist:[38,39,153],reset_period:96,resolut:[27,92,96,116,130,131,132,153,160,165,167,168,171,182,183,185],resolv:[22,24,25,94,152,154,176,186],resour:162,resourc:[27,28,86,96,104,145,154,155,158,161,163,168,169,170,172,174,175,180,183,186],respawn:[94,174,187],respawn_delai:187,respect:[4,28,100,111,153,154,159,166,167,170,171,173,174,186,189],respond:[0,175],respons:[20,22,24,25,28,38,39,40,84,94,154,158,163,167,175],rest:[19,38,39,96,128,146,156,170,171,172,175,180],restart:145,restrict:[28,84,114,153,155,156,165,174,185],result:[9,17,20,27,28,55,56,78,90,96,99,101,102,105,107,148,152,153,158,159,160,163,165,174,175,177,178,188,189],resultstatu:158,resum:155,retain:[20,60,101,102,130,131,132],retick:20,retrain:4,retransit:154,retreiv:10,retri:[18,22,24,25,75,165],retriev:[161,162,163],retrospect:154,retrospective_penalti:[131,132],retry_attempt_limit:96,retryuntilsuccesful:23,retryuntilsuccess:23,retryuntilsucessful:23,retun:[96,154,174],reus:[28,145,158,173,175],revers:[90,96,99,103,106,131,132,154,156,175,185],reverse_penalti:[131,132],reversing_en:90,revert:179,review:[0,13,145,146,148,163,174],revisit:[146,155],rewrittenyaml:[153,183,185],rfid:27,rgb:171,rgba:173,rgbd:9,rich:28,right:[28,96,105,106,131,132,148,149,154,170,172,177,178,180],right_joint:170,right_wheel_est_vel:170,righthand:128,rigid:[173,174],rise:90,roam:168,robbin:76,robin:[20,165],robocup:181,robot:[1,2,4,5,6,7,8,9,10,12,13,14,19,20,21,22,23,24,25,26,27,28,31,38,39,44,50,51,55,56,59,61,67,77,79,82,83,84,85,86,87,89,90,91,92,96,99,100,103,104,106,107,108,111,112,114,116,123,124,125,126,127,129,130,131,132,133,134,135,136,137,138,140,141,142,146,149,150,151,152,153,155,160,161,162,163,165,167,171,172,175,176,178,179,180,181,182,183,185,186,187,188,189],robot_base_fram:[51,59,61,77,86,87,92,101,102,104,158,159,160,163,170,171,176],robot_descript:[170,173],robot_fram:56,robot_loc:[15,170,172],robot_localization_nod:170,robot_model_typ:[85,154],robot_nam:174,robot_navig:27,robot_radiu:[92,160,168,171,174],robot_sdf:174,robot_state_publish:[171,172,173],robot_state_publisher_nod:[170,173],robotech:90,roboticist:28,robotmodel1:173,robotmodel:173,robust:[4,6,28,188],rocker:146,role:[14,28,159,163,167,168,179],roll:[86,92,95,96,143,145,166,170,174,188],rolling_window:[92,171],room:[10,96,182,183,185],root:[18,19,20,21,22,23,24,25,26,88,144,145,146,154,158,159,161,162,163,170,171,173,181,188],root_kei:[183,185],ros1:[150,152,153,171],ros2:[143,149,154,158,160,161,162,163,168,170,171,172,173,177,178,179,180,181,182,183,184,185,186,187],ros2_control:170,ros:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,144,147,148,149,150,151,152,153,154,155,156,157,158,159,160,161,162,163,164,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189,190],ros__paramet:[59,61,83,84,85,86,87,90,91,92,93,94,95,96,97,98,99,100,101,102,104,105,106,107,108,109,111,114,130,131,132,152,153,156,158,159,161,162,163,167,170,171,176,178,183,185,186,187,189],ros_distro:144,ros_w:144,roscon:[1,184,186],rosdep:[143,144,145],rosdistro:143,rosout:170,rot_stopped_veloc:126,rotat:[27,28,29,54,85,86,90,96,99,106,119,123,124,130,132,141,155,161,165,166,167,170,172,173,190],rotate_to_heading_angular_vel:[99,100,189],rotate_to_heading_min_angl:99,rotatetogo:93,rotatetogoalcrit:93,rotation_penalti:132,rotational_acc_lim:[86,158],rotationshimcontrol:[100,189],rough:[99,100,154,173,174,189],roughli:[96,103,149],round:[20,76,84,165,169],roundrobin:[19,22,23,24,25,88],rout:[3,10,27,28,96,163,166,174,175],route_error_code_id:175,route_id:175,route_msg:175,route_serv:175,route_tim:175,routeserv:175,rpp:[167,174,189],rpy:[171,173],rsj:150,rst:165,ruffin:[14,145,150],ruffsl:14,rule:[10,28,161,162,172],run:[0,3,4,7,9,14,17,20,27,28,74,77,80,82,85,86,91,94,95,96,103,128,131,132,143,144,145,146,148,152,153,154,165,167,169,172,174,175,177,179,180,182,184,187,188],runarg:145,runtim:[28,153,154,158,159,160,161,162,163,186],rviz2:[163,173,182],rviz:[17,149,160,161,162,163,169,170,174,178,184,185,188],rviz_common:173,rviz_config_fil:174,rviz_default_plugin:173,rviz_nod:[170,173],rvizconfig:173,ryzhikov:165,safe:[9,13,28,99,150,153,158,159,167,171,172,174],safer:9,safeti:[0,1,28,84,89,94,151,152,153,165,166,174,183,184,187],sai:[11,19,20,28,148,179],said:167,sake:19,salt:[155,178],sam_bot:[168,170,171,173],sam_bot_descript:[168,170,171,173],sambot:168,same:[11,17,19,27,28,60,62,83,84,85,87,90,96,99,106,131,132,145,146,148,149,151,152,154,155,156,158,160,163,171,173,174,175,179,180,183,185,186,187,189],sampl:[6,28,96,100,118,128,155,156,167,168,170,171,174,181],samsung:14,san:14,sandbox:184,sarthak:165,satisfact:96,satisfi:170,sausag:146,save:[85,95,128,131,132,152,153,154,165,168,173,174,177,181,183,184,185,188],save_images_dir:128,save_map:152,save_map_timeout:[95,153],save_pose_r:85,saver:[29,108,111,114,153,183,185],savitzki:[29,165],savitzky_golay_smooth:101,savitzkygolaysmooth:101,scalabl:28,scale:[9,28,93,96,99,101,117,133,134,135,136,137,138,139,140,141,142,153,165,172,173,174,183,185,187],scale_veloc:106,scaling_spe:117,scan:[6,9,27,83,84,85,92,165,171,172,187],scan_top:[85,171],scanner:[6,83,84,112,116,171,187],scenario:[19,23,167],scene:[28,96,151],schema:[144,145],scheme:[8,171],school:28,scope:[4,145,170,171,181,187],score:[96,117,133,134,135,136,138,139,140,167,174],scratch:145,screen:[154,158,170,171,173,175,179,180,183,185,187,188],script:[95,145,155,165,183,185,187],sdf:[154,170,171],sdl:151,se2:[96,111,131,132,150,154,165,174],search:[28,56,96,99,100,103,117,130,131,132,143,153,154,167,174,189],sec:[82,159,184],seccomp:145,second:[9,19,20,22,24,25,28,30,31,44,52,54,68,69,74,75,79,84,87,91,94,95,96,100,127,128,130,131,132,153,154,159,165,170,171,172,175,177,178,183,185],section:[18,19,28,90,96,147,148,150,154,156,160,165,167,168,169,170,171,172,173,174,175,178,179,185],secur:[27,28,145,147],see:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,17,19,20,23,28,30,31,41,42,44,45,52,54,66,83,84,87,89,90,93,96,99,100,103,105,106,112,116,132,143,144,148,149,150,152,153,154,155,156,160,161,162,163,165,166,167,168,170,171,172,173,174,175,176,177,179,180,181,182,183,184,185,186,188,189],seek:[7,150],seem:96,seen:[18,23,103,154,159,160,170,175,188],segment:[90,96,101,145,167,168,171,176,178],select:[2,3,5,7,18,28,43,46,49,53,83,84,85,96,97,99,100,105,108,109,110,111,112,113,114,115,116,130,131,132,145,146,153,155,159,160,165,168,169,171,173,176,178,179,180,181,183,185,188,189],selected_control:43,selected_goal_check:46,selected_plann:49,selected_smooth:53,selector:[22,24,25,165],self:[144,146],self_client_:163,semant:[0,27,150,153,172,175],send:[0,9,27,91,92,99,106,154,158,159,163,181],send_goal:158,send_messag:158,send_sm:158,sendsm:158,senior:148,sens:[172,186,188],sensibl:111,sensit:[6,108,155],sensor:[1,5,7,9,22,24,25,28,83,84,89,92,112,116,145,150,152,153,155,165,167,168,169,170,172,173,174,175,178,186,187],sensor_driv:175,sensor_fram:[112,116,173],sensor_msg:[64,65,84,170],sensorplugin:170,sent:[63,106,154,155,158,163,181],sentin:163,separ:[17,28,83,84,92,96,111,145,150,153,154,160,170,172,175,179,180,183,184,188],separet:156,seper:[176,179],sequenc:[19,20,21,22,23,24,25,26,88,96,145,155,165,170,175,176,181],sequencestar:[23,159],sequenti:150,seri:[168,170,179],seriou:[174,179],serious:148,serv:[19,23,150,154,171],server:[10,11,13,17,18,19,20,23,27,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,52,53,54,57,71,72,73,79,85,87,92,93,94,96,101,102,107,108,111,114,117,118,119,120,121,122,123,124,125,126,133,134,135,136,137,140,141,142,143,149,150,151,153,158,159,160,161,162,163,165,166,170,174,176,179,180,186,187,188,189,190],server_nam:[30,31,32,33,34,35,36,37,41,42,44,45,47,48,54,57,153],server_timeout:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,54,57,66,87,153],servic:[20,28,32,33,34,35,36,37,38,39,40,50,85,95,99,145,146,150,152,153,155,158,165,167,170,177],service_nam:[19,22,23,24,25,32,33,34,35,36,37,38,39,40,50,88,159],servicet:154,session:[130,131,132,145,179],set:[1,2,3,9,10,13,17,18,22,24,25,27,28,30,31,41,42,44,45,52,54,56,58,65,83,85,90,91,92,94,95,96,97,99,103,105,106,107,108,112,114,115,116,117,130,131,132,143,144,145,146,148,149,150,152,153,154,155,156,158,159,160,161,162,163,165,169,174,175,176,177,179,180,181,182,183,184,185,186,187,189],set_camera_info:177,set_initial_pos:85,set_pos:170,setcost:27,setcostmap:27,setinitialpos:[27,154],setplan:161,setspeedlimit:161,setup:[2,28,143,144,145,146,149,160,168,171,172,173,174,175,179,183,184,185,187],sever:[17,50,84,88,89,96,103,145,148,153],shadow:182,shape:[83,84,103,150,155,167,168,169,173,174,183,185,187],share:[11,28,84,86,87,104,145,149,154,156,158,160,161,162,163,170,171,173,174,182,189],shared_ptr:[154,158,161,163],sharedptr:[154,163],sharp:[156,174],sharper:99,sheep:[131,132,154],shelf:27,shell:145,shelv:27,shepp:[90,131,153,165,167],shift:[145,146],shim:[29,165,166,174,190],ship:[16,27],shoot:28,short_circuit_trajectory_evalu:[93,117],shortcut:[99,131,132,154,158,160,161,162,163],shorten:155,shorten_transformed_plan:[117,155],shorter:[23,55,56,131,132,165,173,181],shortest:[28,167],should:[1,2,3,6,9,11,18,19,23,28,71,72,73,75,82,83,87,90,92,95,96,99,106,109,112,114,116,131,132,146,148,149,151,152,153,154,155,158,159,160,161,162,163,168,170,171,172,173,174,175,176,178,179,180,181,182,183,184,185,187,188,189],shouldn:96,shovel:28,show:[2,27,114,146,149,154,158,159,160,161,162,163,167,168,170,171,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187],shown:[13,19,27,96,148,149,153,159,163,167,168,170,171,175,176,181,185,187,188],shrijit:150,shut:[27,28,175],shutdown:[28,154,175],shuttingdown:175,sid:158,side:[26,38,39,92,96,128,145,171,173,175,178,180,188],sidebar:[148,177,180],siemen:188,sig:179,sight:[101,167],sigma_hit:85,sign:[0,106,148],signal:[9,101,165,180],signatur:[159,163],signific:[8,9,96,174],significantli:[7,9,18,23,24,25,79,96,100,154,156,165,174,189],silent:153,sim_tim:[93,121,122],simiar:172,similar:[7,9,10,20,22,24,27,28,83,95,96,103,144,146,153,154,159,167,170,171,173,174,176,179,186,188,189],similarli:[22,24,83,89,156,170],simpl:[3,28,29,101,131,132,146,148,150,151,158,159,160,162,165,167,168,172,173,174,176,179,181,184,188,189],simple_smooth:[52,102,104,176],simplegoalcheck:[45,91,93,99,100,117,153,165,189],simpleprogresscheck:[91,93,99,100,155,165,189],simpler:[172,173],simplesmooth:[53,102,104,176],simplest:159,simpli:[18,96,145,148,153,154,158,159,170,173,174,179,183,185,186,188],simplic:183,simplifi:[6,149,152,159,161,163,179],simul:[1,2,3,4,5,6,7,9,10,11,12,13,17,84,87,96,100,121,122,143,149,156,158,160,161,162,163,168,169,173,174,179,180,182,183,184,185,186],simulate_ahead_tim:[86,100,158,189],simulation_time_step:[84,86],simultan:[145,160,171,183,185],sinc:[6,28,90,96,99,100,102,111,131,132,153,154,160,163,167,168,169,170,171,172,173,174,175,176,179,183,185,187,188,189],singh:[99,150,165],singl:[11,17,20,22,24,25,27,28,91,95,107,148,151,152,153,154,159,160,162,165,170,171,172,173,174,175,176,179,180,186],singletrigg:[88,153],singular:174,sister:153,sit:9,situat:[1,10,19,22,24,25,28,84,99,149,150,153,154,165,168,171,174,176,179,180],size:[27,28,38,39,131,132,154,160,166,167,168,170,171,173,177,178,183,185,186],skew:177,skid:[153,167],skill:[1,2,3,4,5,6,7,8,9,10,11,12,13,179],skillset:7,skinni:174,skip:[85,96,158,170],skirt:154,slack:[0,14,28,148],slam:[6,15,92,150,151,152,171,172,174,179,182,190],slam_toolbox:[15,179,184],sleep:[84,129,159],slide:173,slider:[173,183],slight:101,slightli:[96,101,106,130,131],slop:177,slow:[84,85,96,99,114,141,153,155,156,174,179,185,187],slowdown:[84,187],slowdown_ratio:[84,187],slower:[83,84,178],slowing_factor:[93,141],slowli:96,smac:[29,90,96,99,100,111,153,166,167,168,189],smac_plann:99,smacplann:165,smacplanner2d:[103,130,153,165],smacplannerhybrid:[103,131,154,165],smacplannerlattic:[103,132,165],small:[96,106,131,150,152,155,163,165,166,168,170,173,174,178,182,189],smaller:[13,19,28,99,109,131,132,154,183,185],smart:[28,108],smooth:[21,27,28,52,82,90,96,100,101,102,104,106,130,131,132,150,153,154,155,165,170,174,176,189],smooth_path:[131,132],smoothed_path:[27,52,176],smoothed_path_in_collis:[73,155],smoother:[17,29,52,53,73,99,130,131,132,150,156,163,166,167,175,190],smoother_error_cod:[73,87,176],smoother_id:[27,52,176],smoother_plugin:[90,101,102,104,176],smoother_selector:53,smoother_serv:[90,101,102,104,175,176],smootherselector:88,smoothing_complet:52,smoothing_dur:52,smoothing_duration_us:52,smoothing_frequ:106,smoothing_path_error_cod:52,smoothli:[96,174],smoothpath:[27,88,90,154,176],sms:158,snippet:[19,158,161,162,163,168,170,171,173,175,179],soc:4,soccer:28,socket:146,soft:[23,96],soften:101,softwar:[1,2,3,4,5,6,7,8,9,10,11,12,13,15,16,99,148,150,155,171,175,179],sole:[156,188],solut:[28,96,131,132,174,178],solv:[23,143,162,179],solver:[90,165],some:[4,7,11,13,18,19,20,22,27,28,43,46,47,48,49,53,83,96,101,103,106,111,131,145,148,151,153,154,159,161,162,163,167,168,170,171,172,173,174,178,179,181,183,188],someon:[11,14],someth:[0,19,20,27,148,154,170,172,179,183],sometim:[19,148,174,188],somewhat:[174,189],somewher:185,sonar:[28,84,155,171,186,187],soon:28,sooner:183,sound:[83,156],sourc:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,28,85,86,87,89,90,91,92,93,94,95,96,97,98,99,100,101,102,103,104,106,107,112,116,143,145,147,148,149,150,154,156,158,159,160,161,162,163,168,169,170,171,172,173,177,179,182,183,184,185,186,187],source_fil:[183,185],source_timeout:[83,84,187],space:[1,4,10,21,28,83,84,85,92,95,96,97,99,105,108,130,131,132,145,146,153,154,165,167,170,174,178,182,183],span:[14,150],sparingli:96,spars:[27,28,165,186],sparse_normal_choleski:90,spatial:[28,153],spatio:[165,186],spatio_temporal_voxel_lay:186,spatiotemporalvoxellay:186,spawn:[145,168,170,171],spawn_ent:[154,170],speak:180,special:[28,79,83,84,91,148,155,159,160,188],specif:[2,3,6,11,17,18,19,22,23,24,25,27,28,31,44,88,92,96,99,145,146,151,152,153,154,155,156,159,161,162,163,167,170,171,172,174,176,177,179,183,184,188,189],specifi:[19,22,23,24,25,27,47,48,56,65,75,83,84,87,92,95,128,129,132,144,145,146,152,153,154,155,159,160,161,162,165,167,170,171,172,174,177,180],speed:[2,7,9,20,26,28,31,44,82,84,86,90,91,92,95,96,99,106,111,119,130,131,132,144,145,153,154,156,161,163,165,167,174,187,190],speed_filt:[92,114,185],speed_filter_mask:185,speed_limit:[91,114,185],speed_limit_top:[91,114,185],speed_mask:185,speed_param:185,speedcontrol:[19,88,152],speedfilt:[92,114,153,185],spend:19,spent:180,sphere:[168,171,173],sphere_inertia:173,spheric:173,sphinx_doc:165,spike:[131,132,154],spin:[11,19,20,22,23,24,25,26,27,28,36,88,142,152,153,154,155,158,159,165],spin_dist:[19,22,23,24,25,26,27,54,88,159],spin_error_cod:54,spinner:11,spiral:[154,174],spiritu:150,spite:170,spline:3,split:[17,152],splitter:173,sponsor:14,spot:[22,24,25,132,149,158],squar:[26,38,39,83,84,92,177],src:[143,144,145,160,170,171,173,179,183,185],ssh:[145,146,179],stabil:[151,152,153,154,155,156],stabl:[99,144,145,153],stabliti:149,stack:[0,3,4,6,7,8,9,11,12,14,15,27,28,77,80,82,91,94,95,98,148,150,151,154,155,161,166,167,171,174,175,179,180,188],stage:[28,145,161],stai:[96,111,167,174,181],stale:[145,153],stall:106,stamp:[128,161,162,184],stand:[84,154],standalon:[109,155,165,178,183,185],standard:[2,6,10,85,96,148,171,172,177,183,185,188],standardtrajectorygener:[93,117],star:[29,167,174],start:[4,5,12,17,20,21,22,24,25,27,28,41,42,56,83,84,90,96,99,100,116,147,148,150,152,153,154,158,160,161,162,163,170,171,172,173,174,175,176,177,178,179,180,181,182,183,185,186,187,188,189],start_controller_server_nod:180,start_costmap_filter_info_server_cmd:[183,185],start_lifecycle_manager_cmd:[183,185],start_map_server_cmd:[183,185],start_sync_slam_toolbox_nod:179,start_time_:163,startup:[5,28,94,143,145,149,152,175,177,183,185],state:[3,15,17,20,22,24,25,27,60,84,90,91,93,94,96,99,100,103,106,108,124,149,152,153,154,158,159,161,162,163,165,167,168,170,171,172,174,175,184,185,188,189],state_top:[84,155],statement:148,static_lay:[92,108,111,114,160,171,178,183,185,186],static_transform_publish:[168,172],staticlay:[92,171],station:[28,167],statist:[4,9,180],statu:[18,28,148,154,158,159,183],status1:173,status:[27,163],std:[58,152,154,158,159,161,162,163,179],std_msg:[108,127,170],stddev:[170,171],stdin:179,steep:105,steeper:105,steer:[90,130,154,171,174],step:[20,28,84,86,96,171,173,179,180],step_siz:27,stereo:[84,177],steve:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,96,150,165,179],stevemacenski:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,184,186],steven:150,sticki:1,still:[19,20,27,94,99,106,111,143,145,146,153,154,155,156,170,171,173,174,179,183],stl:179,stl_vector:179,stop:[9,21,28,74,84,89,94,96,106,107,117,126,141,152,153,155,173,187],stop_on_failur:[107,151,153],stop_pub_timeout:[84,187],stoppedgoalcheck:[91,165],storag:[145,163],store:[85,92,112,116,145,150,155,160,161,163,171,172,180],stori:10,strace:145,strafe_theta:140,strafe_x:140,straight:[131,132,162,173,174,176],straightforward:171,strategi:148,stream:154,streamlin:[144,146],stretch:146,strictli:[6,132,155],stride:8,string:[30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,56,57,59,61,70,77,78,83,84,85,86,87,90,91,92,94,95,96,98,100,104,106,107,108,111,112,113,114,115,116,117,127,128,131,132,134,135,138,139,152,155,158,159,160,161,162,163,170,175,186],strive:[14,148],stroke:[2,169],strongli:28,structur:[6,8,19,28,150,155,163,167,172,173,175,185,186,188],stuck:[1,19,22,24,25,28,30,31,44,54,67,154,165,174],student:[7,148],studio:146,stutter:174,stvl:190,stvl_layer:[92,186],style:[22,24,25,174,186],sub:[0,22,24,25,154],subcommand:145,subject:[28,96,170],submit:[13,148,165],suboptim:[96,174],subproject:13,subscrib:[28,43,46,49,53,64,65,78,84,85,91,113,115,153,170,171,181],subscribe_to_upd:[92,115],subscript:[78,83,84,153,163,165,170,175],subsect:[145,171],subsequ:[20,28,85,145,165],subset:180,subsiqu:[131,132],substanti:[1,96,148,151,174],substitut:[87,173,181,183,185],subtleti:163,subtli:154,subtre:[18,20,22,23,24,25,28,38,39,40,88,159,165],succe:[19,20,74,75,165],succeed:[27,81,154,158,162],success:[14,19,20,23,28,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,75,96,153,154,155,158,159,165,173,178,189],successfulli:[1,19,28,154,158,163,170,172,173,175,181],successor:[96,150,155],sucessfulli:172,sudo:[144,149,170,171,173,177,180,184,186],suffici:[4,19,28,96,132,141,163,178,180],suffix:180,suggest:[20,90,96,167,172,173],suit:[0,145],suitabl:[90,100,154,165,167,172,189],sum:[85,133,134,135,136,138,139,167,173],sum_scor:[133,136],summar:[167,172,174],summari:17,summer:[5,11],superior:155,suppli:[11,28,77,80,82,87],support:[2,6,13,14,28,43,46,49,53,83,99,103,143,145,146,150,151,152,155,165,167,171,173,174,178,183,185,186,188],suppos:172,sure:[1,2,7,12,27,96,112,116,143,144,145,148,153,156,160,163,165,168,170,171,174,177,178,179,182,183,184,185,186,187],surfac:28,surpris:189,surround:167,survei:150,susbcrib:128,sustain:28,swap:[154,155],sweep:[173,174],symbol:179,symlink:[144,160,183,185],symmetr:156,symmetri:154,sync:188,sync_slam_toolbox_nod:179,synchron:28,syntax:[145,156,173,179],sysdep:179,system:[1,6,7,8,10,11,12,19,20,22,24,25,28,84,85,94,96,144,145,146,148,149,150,151,154,163,167,171,172,173,174,175,176,177,179,180,182],systemat:175,systemdefaultsqo:163,sysv:179,tab:[143,168,171],tabl:[154,160,161,163,169,174,175],tackl:[168,169],tag:[144,145,154,159,170,171,173],tailor:167,take:[1,9,12,17,18,22,23,27,28,41,42,45,47,48,61,79,83,84,85,91,94,96,98,100,101,102,107,128,130,145,148,149,151,153,154,155,158,159,161,162,163,165,170,171,172,173,174,175,176,177,178,179,180,181,182,185,189],taken:[4,75,83,84,90,96,114,128,153,160,163,183,185],talk:[1,145,150,170,172,179,184,186],talker:143,tangent:[4,177],tangenti:177,tar:177,target:[6,96,99,114,145,146,152,153,167,173,179,181,182,185,188],task:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,18,22,23,24,25,27,28,51,78,84,87,89,96,100,107,148,150,151,153,155,158,159,163,167,168,169,171,174,176,181,188,189,190],taskexecutor:27,taskresult:[27,154],tb3:[150,156],tb3_simulation_launch:[149,158,160,161,162,163,174,178,179,181,183,184,185,187],tbb:7,tcp:146,team:[14,146,181],tear:106,teardown:[28,167],teb:[3,96,151,155,165,167,174,189],teb_local_plann:152,teblocalplann:152,technic:[8,22,24,25,148,158,160,161,162,163,183],techniqu:[3,4,6,28,84,101,102,103,153,171,174],technolog:[8,14],tediou:173,teleop:[0,27,30,86,165],telepres:1,tell:[28,148,158,159,160,170,179],temperatur:96,templat:[103,144,148,153,159,163,169,173,179],tempor:[165,186],temporari:[22,23,24,25,183,185],tend:189,term:[96,148,163,171,172,183],termin:[90,102,130,131,132,143,149,152,158,168,170,171,177,179,180,181,182,184],terminatependinggo:163,test:[0,3,4,6,17,86,96,132,145,148,166,170,177,181,184,186,188],text:[158,160,186],tf1:173,tf2:[28,152,169,170,172,173,174],tf2_echo:[170,172],tf2_msg:170,tf2_ro:[161,168,170,172],tf2_tool:171,tf_:[161,162],tf_broadcast:85,tf_static:154,tfmessag:170,than:[17,20,22,24,25,28,55,56,61,65,79,84,85,92,94,96,98,99,100,108,109,131,132,145,152,153,154,155,156,161,163,165,172,174,178,179,180,181,183,184,187,189],thank:14,thei:[0,7,19,20,22,24,25,28,83,84,87,94,96,103,142,145,146,148,150,152,153,154,155,158,159,161,162,163,167,169,170,171,172,173,174,175,179,180,183,187,188],theinput:170,them:[4,7,22,27,28,83,91,96,107,111,112,116,132,145,146,148,150,151,153,154,155,156,158,159,160,161,162,168,171,172,173,174,175,176,179,180,182,183,184,187,188,189],themselv:[163,188],theoret:96,theori:96,therebi:148,therefor:[20,23,83,96,173,174,175,179,183,185,188],theta:[27,29,100,101,106,153,165,167,174,189],theta_scal:140,thetastarplann:[105,165],thi:[0,1,2,4,5,6,7,9,10,11,13,14,15,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,43,46,49,51,53,54,57,60,71,72,73,79,81,83,84,85,86,87,88,90,91,92,94,95,96,97,98,99,100,101,102,104,105,106,108,109,110,111,112,113,114,115,116,130,131,132,133,145,146,147,148,149,150,151,152,153,154,155,156,158,159,160,161,162,163,165,166,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],thing:[13,28,146,154,155,160,161,162,170,173,174,179,180,185],think:[0,8,28,174],third:[74,161,183,185],those:[9,14,28,101,145,154,167,171,173,174,175,176,179],though:[20,22,96,174,175,183,187],thought:[28,154,159],thread:[7,11,13,27,28,179],three:[26,28,103,155,172,174,175],threshhold:95,threshold:[61,84,91,95,96,99,100,108,137,154,165,182,183,185,189],threshold_to_consid:[96,156],throttl:[80,152,165],through:[1,9,17,18,19,20,23,24,25,27,28,29,41,94,96,105,112,116,131,132,145,148,149,150,152,153,154,155,156,160,165,167,169,170,171,172,173,174,175,179,180,183,184,185,186,189],throughout:[2,60,145,151,154,173,175],thrown:154,thu:[83,84,90,96,105,106,167,170,171,180],thusli:[168,174,189],tick:[19,20,22,23,24,25,28,60,74,77,80,81,82,154,159,165],ticket2:[10,11,13],ticket:[1,4,7,9,10,11,13,14,28,143,148,152,153,154,174,179,188],tie:4,tied:[28,132],tight:[100,132,167,174,189],tighter:174,till:74,tilt:177,time:[0,1,3,4,6,7,8,9,11,14,17,19,20,21,22,23,24,25,26,27,28,30,31,44,52,54,56,57,69,74,75,83,84,85,86,87,96,99,100,101,102,103,106,108,111,113,114,121,122,123,125,127,128,129,130,131,132,141,144,145,146,148,151,152,154,156,159,160,163,165,166,167,168,170,172,174,175,176,178,179,180,181,182,183,185,186,187,188,189],time_allow:[26,27,30,31,44,54,86,154],time_before_collis:84,time_granular:122,time_step:96,timedbehavior:158,timeexpir:88,timeexpiredcondit:152,timelin:148,timeout:[30,31,32,33,34,35,36,37,38,39,40,41,42,44,45,47,48,50,54,57,72,73,84,87,91,94,95,106,127,152,158,159,187],timer:[68,165,171],timestamp:[27,128,170],timestep:96,timezon:148,tini:101,tip:[169,174,183],tireless:14,titl:150,tmp:[128,145,177],to_entri:145,to_numb:158,togeth:[20,28,170,172],toggle_filt:155,token:158,tol:165,toler:[19,28,56,61,86,87,90,92,96,97,99,100,102,104,115,117,124,126,130,131,132,141,153,154,156,162,165,176,182,189],tom:15,ton:179,too:[19,96,105,131,132,153,154,156,174,176],took:105,tool:[2,4,15,28,143,144,145,146,148,150,152,153,163,169,171,172,173,179,180,183],toolbar:181,toolbox:[28,151,171,174,179,184],top:[5,7,11,17,19,92,158,160,161,162,163,172,176,177,178,180,183,185,188],topic:[0,20,21,22,24,25,28,43,46,49,53,64,65,78,83,84,85,86,87,89,91,92,95,104,106,108,111,112,113,114,115,116,117,127,128,131,148,151,152,153,154,155,156,163,165,168,169,170,171,172,173,175,176,177,180,181,182,183,184,185,186,187],topic_nam:[43,46,49,53,95,183,185],torqu:106,total:[28,31,96,130,131,132,178],total_number_of_loop:162,touch:136,toward:[21,67,83,84,90,96,100,131,132,154,156,162,165,174,177,182,189],trace:179,track:[6,27,28,92,96,99,100,148,150,154,155,161,163,165,174,176,179,189],track_unknown_spac:[92,171,186],tracker:[0,96],trackingrout:27,tractabl:152,trade:[96,189],tradeoff:130,traffic:[151,165],trait:[156,174],trajectori:[3,4,10,84,89,106,117,120,122,133,134,135,136,138,139,140,153,155,162,167,168,174],trajectory_generator_nam:117,trajectory_point_step:96,trajectory_step:96,trajectoryvisu:96,tranform:171,trans_stopped_veloc:[93,126,141],transfer:5,transform:[5,15,28,70,83,84,85,86,87,92,96,99,104,108,111,114,117,143,149,150,152,153,154,161,165,168,169,170,171,173,174,183,184],transform_timeout:[86,101,102,104,158,176],transform_toler:[56,59,61,83,84,85,86,87,92,93,96,99,104,108,111,114,115,117,161,163,186,187],transform_tolerance_:161,transformavail:88,transformglobalplan:161,transit:[28,94,101,152,154,163,174,175,176,180,189],translat:[31,44,85,99,119,123,153,155,165,170,172,174],transpar:148,transport:145,transvers:172,travel:[20,28,44,59,77,96,130,131,132,154,165,170,171],travers:[26,28,96,130,131,132,154,172],treat:[92,186],tree:[1,2,11,17,21,22,23,24,25,26,29,30,31,47,48,54,57,59,61,74,75,76,77,78,79,80,81,82,143,149,150,151,154,160,163,164,167,171,172,173,175,176,190],treenod:188,treenodesmodel:188,trend:[131,132],tri:[28,152,161],triangl:[83,84],triangular:113,trick:[169,179],trig:154,trigger:[11,19,20,22,24,25,28,50,77,79,81,83,84,96,99,100,108,145,152,153,154,155,165,175,176,187,189],trim:56,trinari:[183,185],trinary_costmap:92,trivial:[7,28,148,155,158,187,188],troubleshoot:144,truli:[11,174],truncat:[21,55,56,90,165],truncated_path:[21,55,181],truncatepath:[21,88,152,181],truncatepathloc:[88,90],trust:[11,146,150],trytoresolvesmoothererrorcod:176,tsc:148,tudela:165,tunabl:29,tune:[1,9,26,95,96,100,105,154,169,183,185,187,189],tunnel:146,turn:[26,90,96,99,106,108,131,132,145,153,154,155,156,165,167,173,174,176,178,179,189],turtl:95,turtlebot3:[144,149,158,159,160,161,162,163,176,178,182,183,184,185],turtlebot3_bringup:[182,184],turtlebot3_gazebo:149,turtlebot3_model:[149,182,184],turtlebot3_world:[95,149,183,185],turtlebot:[149,190],tutori:[3,8,15,17,19,83,84,87,88,153,155,165,166,167,168,169,170,171,172,173,174,175,179,180,187,188,189],tutorials_w:[183,185],tweak:145,twilio:158,twirling_cost_pow:96,twirling_cost_weight:96,twirlingcrit:[93,96],twist:[0,30,106,161,170],twiststamp:[0,161],twistwithcovari:170,twistwithcovariancestamp:170,two:[3,19,20,28,75,83,84,90,97,103,105,130,145,153,154,155,158,161,162,163,167,170,171,172,173,175,178,180,185,186,187],two_d_mod:170,txt:[158,160,161,162,163,170,171,173,177,179,180],type:[8,18,27,28,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,69,70,71,72,73,75,77,78,79,80,82,83,84,85,86,87,90,91,92,94,95,96,97,98,99,100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,145,146,149,150,152,153,154,158,159,160,161,162,163,165,167,170,171,173,174,175,176,178,179,181,183,185,186,187,188,189],typenam:[154,163],typic:[9,19,20,28,83,84,131,132,148,154,161,168,170,172,174,178,183,184,185,189],ubuntu:186,udrf:2,uint16:[30,31,41,42,44,45,47,48,52,54,175],uint8:27,ukf_localization_nod:170,ukf_nod:170,ultim:23,unabl:[0,130,154],unaccept:[83,84,178],unaffect:145,unchang:145,unclear:28,uncom:[90,144,145],unconfigur:[28,175],under:[1,2,3,4,5,6,7,8,9,10,11,12,13,17,21,87,112,116,145,146,148,152,153,154,155,158,159,165,167,168,170,171,173,176,179,186],underlai:[144,145],underli:[28,186],understand:[11,22,24,25,28,105,148,163,178,179,180,183,186],understood:183,undesir:183,unfair:8,unfamiliar:[11,28],unfold:185,unifi:173,unintend:145,uniqu:[22,24,25,28,145,150,152,153,156,158,159,163],unique_tb3_simulation_launch:156,unit:[28,87,94,148,166,172],univers:[5,172],unix:179,unknown:[28,71,72,73,92,97,105,110,116,130,131,132,155,175,183],unknown_cost_valu:92,unknown_threshold:[92,116,186],unless:[19,20,94,99,132,148],unlesscondit:[170,173],unlik:[19,83,158,178],unmodifi:145,unnecessari:[96,178],unord:155,unpredict:185,unreach:[130,131,132],unrespons:175,unsaf:[131,132,154],unscent:170,unsign:[58,71,72,73,160],unsmooth:176,unsmoothed_path:[52,176],unspecifi:[84,170],unsuit:148,unsynchron:177,untick:20,until:[19,20,21,27,28,74,84,100,117,131,132,143,145,153,161,163,165,170,179,181,186],untouch:[152,161],unus:96,unwant:[154,185],unzip:177,updat:[6,7,11,12,17,19,20,21,28,60,68,78,85,92,103,111,115,145,148,151,154,155,158,159,160,161,163,165,170,172,174,178,181,184,185,188],update_footprint_en:186,update_frequ:[92,171],update_min_a:85,update_min_d:85,update_r:[170,171],updatebound:160,updatecontentcommand:145,updatecost:160,updated_go:[21,78,181],updatego:152,updater:171,updatewithaddit:160,updatewithmax:160,updatewithoverwrit:160,updatewithtrueoverwrit:160,upgrad:[145,152],upon:[0,3,19,20,75,148,154,162,173],upper:99,upsampl:90,urdf:[2,28,149,168,169,172,174,184],urdf_config:173,usag:[11,27,108,145,172,173,175],usb:145,use:[0,1,3,4,8,9,10,11,13,17,20,21,22,23,24,25,27,28,41,42,45,52,65,78,83,84,85,86,87,90,91,92,96,97,98,99,100,101,102,104,106,111,112,116,117,131,132,133,143,145,147,148,149,150,151,152,153,154,155,156,158,159,160,161,162,163,167,168,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],use_approach_linear_velocity_sc:154,use_astar:[97,153,162],use_collision_detect:99,use_composit:[154,174,179,180],use_cost_regulated_linear_velocity_sc:99,use_final_approach_orient:[97,105,130],use_fixed_curvature_lookahead:[99,155],use_interpol:99,use_maximum:92,use_namespac:174,use_path_orient:[96,156],use_rclcpp_nod:154,use_regulated_linear_velocity_sc:99,use_respawn:[154,174,187],use_robot_state_pub:174,use_rotate_to_head:99,use_rviz:174,use_sim:182,use_sim_tim:[87,90,91,92,93,99,100,105,130,131,132,158,159,160,162,163,168,170,171,174,179,180,182,183,185,186,187,189],use_simul:174,use_start:[27,153],use_velocity_scaled_lookahead_dist:99,used:[0,1,5,13,14,15,17,18,19,20,22,23,24,25,26,27,28,30,31,41,42,43,46,49,51,52,53,54,56,57,65,76,77,80,82,84,85,90,92,95,96,103,107,112,114,116,131,132,144,145,146,150,151,152,153,154,155,156,158,159,160,161,162,163,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,183,185,187,188],useful:[0,20,21,22,24,25,28,78,84,85,96,101,145,146,153,154,156,159,168,170,171,172,173,174,175,180,181,183,185,186,188],useless:19,user:[1,2,3,7,9,14,18,22,23,24,25,27,28,29,75,79,83,84,85,102,107,113,127,145,146,148,152,153,154,155,163,165,169,171,174,175,179,180,184,186,189],userenvprob:145,uses:[5,6,17,20,28,47,48,83,84,85,90,92,96,97,101,103,112,116,143,150,151,152,155,156,158,159,165,167,170,171,172,173,174,177,182,186],using:[4,5,6,7,8,9,10,13,14,16,18,19,21,22,24,25,26,27,28,32,33,34,35,36,37,41,42,45,50,84,85,87,88,89,90,95,96,99,101,102,103,105,107,111,128,131,132,143,144,145,146,149,150,152,153,154,155,158,159,160,161,162,163,165,167,168,172,174,175,176,177,179,180,181,182,184,185,186,187,188,189],usr:[179,186],usual:[20,28,43,46,49,103,145,153,160,170,172,175,179,180,183],util:[22,23,24,25,28,96,145,150,153,154,155,156,159,167,168,170,173,180,183,185,186],valgrind:[179,180],valid:[28,66,83,84,85,90,108,111,112,114,116,131,132,150,155,163,165,171,174],valu:[43,46,49,53,65,83,84,85,87,90,91,92,95,96,99,102,105,108,112,113,114,116,130,131,132,145,148,153,154,155,158,159,160,161,162,163,165,168,170,171,172,173,174,176,178,179,182,183,185,187,188,189],valuabl:[7,11,148],vargovcik:165,vari:[96,99],variabl:[13,18,41,42,45,47,48,52,61,79,85,87,113,143,144,145,149,158,159,161,162,171,176,183,185,186,188],variant:[3,6,28,96,99,153,165,167],variat:[99,153,163,165,167,170],varient:153,varieti:[28,158],variou:[5,28,86,96,104,144,145,154,155,165,166,170,172,173],vast:[154,158],vcs:144,vcstool:144,vector:[22,28,41,47,51,83,84,86,87,91,92,94,96,97,98,101,104,105,106,111,112,113,116,117,130,154,155,160,162,163,168,179,183,185,186],vectorcrash:179,vehicl:[1,4,96,103,131,132,153,165,167],veloc:[1,4,9,13,29,82,83,84,86,89,91,96,99,100,114,118,119,126,137,140,141,150,153,156,158,161,165,166,167,170,174,187,189],velocity_smooth:106,velocity_timeout:106,velocitysmooth:155,vendor:171,verb:145,verbos:[170,171,174],veri:[6,7,11,14,16,18,22,24,28,96,101,131,148,154,166,168,172,173,174,189],verifi:[4,28,136,146,170,171,173],version:[24,25,28,90,117,143,144,146,149,153,161,171,173],vertex:[83,84,177],vertic:[109,187],vertical_fov_angl:186,via:[13,20,21,22,24,25,28,43,46,49,63,83,84,85,89,103,144,145,146,148,150,154,155,156,158,163,165,172,174,175,176,180,184,186,188],viabl:163,viapoint:[51,165],vicin:170,video:[23,145,160,181,182,186,188],view:[83,84,149,154,173,177,186,187,188],view_fram:171,vigil:146,vio:[28,170,172],violat:20,virtual:[21,84,96,154,158,159,160,161,162,163,170,173],visibl:[158,159,161,162,163,173],vision:[28,90,171],vision_msg:171,visit:[1,28,131,132,148],visual:[2,83,84,87,88,145,146,150,154,170,174,176,180,184,185,186,187],visualis:155,visualization_mark:171,viz_expans:156,vocabulari:20,volatil:173,voltag:65,volum:145,volumet:186,volumetr:165,vornoi:3,voxel:[7,92,155,165,171,178,186],voxel_decai:186,voxel_grid:[171,186],voxel_lay:[92,109,111,153,160,168,171,178,183],voxel_marked_cloud:153,voxel_min_point:186,voxel_s:186,voxel_unknown_cloud:153,voxellay:[92,171],vpitch:170,vroll:170,vscode:145,vslam:150,vslamcomparison2021:150,vtheta_sampl:[93,118],vx_max:96,vx_min:96,vx_sampl:[93,118],vx_std:96,vy_max:96,vy_sampl:[93,118],vy_std:96,vyaw:170,w_cost:90,w_cost_cusp_multipli:90,w_curv:90,w_data:[102,130,131,132],w_dist:90,w_euc_cost:105,w_heuristic_cost:105,w_smooth:[90,102,130,131,132],w_traversal_cost:105,waffl:[149,182,184],wai:[2,9,19,22,24,25,28,79,87,94,96,107,109,131,132,142,144,150,153,154,155,156,168,172,174,175,176,179,184,186,189],wait:[13,19,20,22,23,24,25,27,28,37,85,86,87,88,107,127,129,146,149,151,154,158,159,165,171,175],wait_act:159,wait_at_waypoint:[107,153],wait_dur:[19,22,23,24,25,57,88,159],wait_serv:57,waitact:159,waitatwaypoint:[107,153,165],waituntilnav2act:[27,154],walk:[19,20,28,145],walkthrough:18,wall:174,wallac:[14,165],want:[22,24,25,27,28,83,96,145,153,158,159,160,161,162,163,170,172,173,174,175,176,179,180,182,184,188],warehous:[27,28,168,174,183],warn:[83,98,113,131,152],was_complet:52,watch:149,watchdog:[9,94,137,150,152],water:20,wavefront:[97,154],waypoint:[17,27,29,127,128,129,150,151,153,154,175],waypoint_follow:[94,107,153,175],waypoint_imag:128,waypoint_pause_dur:[107,129,153],waypoint_task_executor:[127,128,129],waypoint_task_executor_plugin:[107,153],waypoint_task_executor_plugin_id:[127,128,129],waypointfollow:154,waypointtaskexecutor:153,weak:161,weakptr:[161,163],wear:106,web:[8,146],websit:[15,19],weigh:[133,134,135,136,137,138,139,140,141,142],weight1:90,weight2:90,weight:[28,56,85,90,96,102,105,130,131,132,140,152,154,156,174,183],welcom:148,well:[0,1,4,6,14,19,20,22,24,25,27,91,95,96,134,138,139,145,152,153,154,156,167,171,172,174,176,177,178,179,183,185,186,188],went:174,were:[11,14,19,28,86,151,152,153,154,155,156,172,173,174,175,183,185,187],what:[2,6,20,28,117,147,148,154,166,170,171,172,173,175,176,182],whatev:160,wheel:[28,170,172,173],wheel_diamet:170,wheel_radiu:[170,173],wheel_separ:170,wheel_width:173,wheel_xoff:173,wheel_ygap:[170,173],wheel_zoff:173,when:[11,19,20,21,22,24,28,56,59,63,65,69,77,79,80,82,83,84,85,86,91,92,94,96,98,99,100,105,106,107,108,111,114,128,131,132,137,141,143,145,146,148,152,153,154,156,158,159,160,161,162,163,165,167,168,170,171,172,173,174,175,177,178,179,180,181,183,185,187,188,189],whenev:[145,146,154,182,184],where:[1,6,10,13,20,23,27,28,83,84,96,102,108,114,116,128,132,133,144,145,148,149,152,153,154,156,159,160,161,162,163,165,168,170,171,172,173,174,175,180,182,183,185,187],wherea:[9,96,155,174,175],wherein:[167,168],whether:[52,83,84,85,90,92,94,96,97,99,101,102,105,106,107,108,109,110,111,112,113,114,115,116,117,120,122,123,124,125,126,127,128,129,130,131,132,133,136,148,151,153,158,160,161,165,170,171,173,174],which:[3,9,19,20,23,25,27,28,29,30,31,41,42,44,45,47,48,54,55,56,57,77,78,80,82,83,84,85,87,90,94,95,96,99,103,106,107,108,109,111,113,114,145,151,153,154,155,156,158,159,160,161,162,163,167,168,169,170,171,172,173,174,175,176,177,178,181,182,183,184,185,187,188],whilst:173,whip:[174,189],white:[14,145,150,178,183],whiter:183,whitespac:173,who:[96,148,163,174,181],whole:[19,56,148,160,171,177,185,187],whose:[90,171],why:[147,179],wide:[4,19,28,158,174],wider:174,widest:145,widget:173,width:[27,92,96,99,160,171,174],wiki:173,wilcox:[14,165],wild:14,willing:174,window:[131,132,154,160,167,168,170,171,172,173,174,177,178,179,180,188],wisdom:174,wise:[28,96,163,174],wish:[0,23,58,84,111,153,154,175,176],within:[10,19,20,22,28,58,83,84,85,89,96,100,130,131,132,145,146,148,154,155,156,160,163,165,170,171,173,174,175,180,186,188,189],withing:154,without:[1,4,14,17,28,56,83,84,90,91,96,101,109,111,145,146,152,153,154,156,160,163,168,169,171,174,179,181,183,184,189],wizard:14,wobbl:[96,131],won:[38,96,153,158,159,161,162,163,168,173,178,183],word:[146,155,161,162,172,178,183],work:[0,1,4,5,6,7,8,9,11,12,13,14,15,16,28,83,88,89,96,99,145,148,149,150,154,155,156,158,159,160,161,162,163,167,168,170,171,172,173,174,176,179,180,183,185,186,187],workflow:[28,145,146],workspac:[143,144,145,146,160,173,177,179,180,181,184,186,188],world:[8,9,27,28,145,149,150,158,170,171,172,174,178,181,183,184,185,186],world_fram:170,world_path:171,worldtomapvalid:27,worldwid:150,worri:[22,24,25,28,146,174,179],worst:12,worth:[22,24,96,174,178],would:[0,1,6,8,14,20,23,28,84,95,99,105,130,131,132,145,146,148,150,153,154,158,159,161,162,163,165,170,172,173,174,176,179,180,183,184,185,186,189],wouldacontrollerrecoveryhelp:[88,155],wouldaplannerrecoveryhelp:[88,155],wouldasmootherrecoveryhelp:[88,155,176],wouldn:[9,174],wrap:[19,27,28],wrapper:[17,28,158,159,179],write:[152,155,156,164,165,167,170,174,175,188],written:[6,28,158,160,161,162,163,171,178,183,185,187,188],wz_max:96,wz_std:96,x11:[145,146],x86_64:[179,186],x_increment:162,x_only_threshold:137,x_pose:174,x_reflect:173,xacro:[170,173],xml:[1,2,17,18,19,28,29,47,48,87,150,152,154,156,158,159,160,161,162,163,170,173,175,181,188],xml_tag_nam:159,xmln:173,xterm:[179,180],xvf:177,xxx:180,xy_goal_toler:[91,93,99,100,124,141,153,189],xytheta:93,xyz:[170,171,173],y_increment:162,y_pose:174,y_reflect:173,yaml:[27,83,84,95,153,154,156,158,159,160,161,162,163,167,168,170,174,175,176,177,178,179,180,182,183,185,186,187,189],yaml_filenam:[95,155,183,185],yaw:[85,170,174,183,185],yaw_goal_toler:[91,93,99,100,124,153,189],year:[6,14,150],yes:179,yet:[6,20,27,96,145,154,172,174],yolact:4,yolo3d:4,you:[0,4,5,6,10,11,12,13,14,18,21,27,28,58,85,87,90,91,95,96,99,103,105,111,132,133,143,144,145,146,148,149,150,153,154,155,156,158,159,160,161,162,163,165,167,168,169,170,171,172,173,174,175,176,177,178,179,180,181,182,183,184,185,186,187,188,189],your:[3,4,5,6,8,9,10,11,12,13,14,18,19,27,28,84,94,95,96,99,100,103,105,106,132,143,144,145,146,148,149,150,152,153,154,155,156,158,160,161,162,163,165,167,168,169,171,172,173,174,175,177,179,180,181,183,184,185,186,187,188,189],your_map:182,your_params_fil:[158,161,162,163],yourself:[148,154,176],yuk:13,z_hit:85,z_max:85,z_pose:174,z_rand:85,z_resolut:[92,116,171],z_short:85,z_voxel:[92,116,171],zero:[84,106,113,114,129,154,159,177,183,185],zmq:154,zone:[9,28,83,84,90,95,111,131,132,153,154,165,171,185,187,190],zurich:5},titles:["Projects for 2021 Summer Student Program","3. Assisted Teleop","1. Create a Configuration Assistant (Analog to MoveIt)","2. Create New Planner and Controller Plugins","1. Navigation Dynamic Obstacle Integration","3. Port Grid Maps to ROS 2 and Environmental Model","6. 2D/3D Localization Improvements","4. Navigation MultiThreading","5. Navigation Branding and Website","5. Navigation Safety Node","6. Semantic Integration","7. Reduce ROS 2 Nodes and Determinism","2. Advanced Navigation Testing Framework","8. Convert Twist to TwistStamped in Ecosystem and Run-Time Configuration","About and Contact","Related Projects","Robots Using","ROS to ROS 2 Navigation","Nav2 Behavior Trees","Detailed Behavior Tree Walkthrough","Introduction To Nav2 Specific Nodes","Follow Dynamic Point","Navigate Through Poses","Navigate To Pose and Pause Near Goal-Obstacle","Navigate To Pose","Navigate To Pose With Consistent Replanning And If Path Becomes Invalid","Odometry Calibration","Simple Commander API","Navigation Concepts","Configuration Guide","AssistedTeleop","BackUp","CancelAssistedTeleop","CancelBackUp","CancelControl","CancelDriveOnHeading","CancelSpin","CancelWait","ClearCostmapAroundRobot","ClearCostmapExceptRegion","ClearEntireCostmap","ComputePathThroughPoses","ComputePathToPose","ControllerSelector","DriveOnHeading","FollowPath","GoalCheckerSelector","NavigateThroughPoses","NavigateToPose","PlannerSelector","ReinitializeGlobalLocalization","RemovePassedGoals","SmoothPath","SmootherSelector","Spin","TruncatePath","TruncatePathLocal","Wait","AreErrorCodesPresent","DistanceTraveled","GloballyUpdatedGoal","GoalReached","GoalUpdated","InitialPoseReceived","IsBatteryCharging","IsBatteryLow","IsPathValid","IsStuck","PathExpiringTimer","TimeExpired","TransformAvailable","WouldAControllerRecoveryHelp","WouldAPlannerRecoveryHelp","WouldASmootherRecoveryHelp","PipelineSequence","RecoveryNode","RoundRobin","DistanceController","GoalUpdater","PathLongerOnApproach","RateController","SingleTrigger","SpeedController","Collision Detector Node","Collision Monitor Node","AMCL","Behavior Server","Behavior-Tree Navigator","Behavior Tree XML Nodes","Collision Monitor","Constrained smoother","Controller Server","Costmap 2D","DWB Controller","Lifecycle Manager","Map Server / Saver","Model Predictive Path Integral Controller","NavFn Planner","Planner Server","Regulated Pure Pursuit","Rotation Shim Controller","Savitzky-Golay Smoother","Simple Smoother","Smac Planner","Smoother Server","Theta Star Planner","Velocity Smoother","Waypoint Follower","Binary Filter Parameters","Denoise Layer Parameters","Inflation Layer Parameters","Keepout Filter Parameters","Obstacle Layer Parameters","Range Sensor Parameters","Speed Filter Parameters","Static Layer Parameters","Voxel Layer Parameters","DWB Controller","XYTheta Iterator","Kinematic Parameters","Publisher","LimitedAccelGenerator","StandardTrajectoryGenerator","PoseProgressChecker","SimpleGoalChecker","SimpleProgressChecker","StoppedGoalChecker","InputAtWaypoint","PhotoAtWaypoint","WaitAtWaypoint","Smac 2D Planner","Smac Hybrid-A* Planner","Smac State Lattice Planner","BaseObstacleCritic","GoalAlignCritic","GoalDistCritic","ObstacleFootprintCritic","OscillationCritic","PathAlignCritic","PathDistCritic","PreferForwardCritic","RotateToGoalCritic","TwirlingCritic","Build Troubleshooting Guide","Build and Install","Dev Container Guide","Dev Containers","Development Guides","Getting Involved","Getting Started","Nav2","Dashing to Eloquent","Eloquent to Foxy","Foxy to Galactic","Galactic to Humble","Humble to Iron","Iron to Jazzy","Migration Guides","Writing a New Behavior Plugin","Writing a New Behavior Tree Plugin","Writing a New Costmap2D Plugin","Writing a New Controller Plugin","Writing a New Planner Plugin","Writing a New Navigator Plugin","Plugin Tutorials","Navigation Plugins","Roadmaps","Setting Up Navigation Plugins","Setting Up the Robot\u2019s Footprint","First-Time Robot Setup Guide","Setting Up Odometry","Setting Up Sensors","Setting Up Transformations","Setting Up The URDF","Tuning Guide","Adding a New Nav2 Task Server","Adding a Smoother to a BT","Camera Calibration","Filtering of Noise-Induced Obstacles","Get Backtrace in ROS 2 / Nav2","Profiling in ROS 2 / Nav2","Dynamic Object Following","Navigating with a Physical Turtlebot 3","Navigating with Keepout Zones","(SLAM) Navigating While Mapping","Navigating with Speed Limits","(STVL) Using an External Costmap Plugin","Using Collision Monitor","Groot - Interacting with Behavior Trees","Using Rotation Shim Controller","General Tutorials"],titleterms:{"2021":0,"case":154,"default":[86,91,92,98,107,153,155],"export":[158,159,160,161,162,163],"long":155,"new":[3,151,152,153,154,155,156,158,159,160,161,162,163,175],"static":[115,172],"while":184,Added:[153,154,155],Adding:[170,171,173,175,176,188],And:25,For:156,Near:23,ROS:[5,11,17,28,92,155,179,180],The:[156,173],Use:154,Uses:155,Using:[16,145,186,187,189],With:[19,25],about:14,academ:28,access:[155,156],ackermann:96,action:[20,28,88,152,153,154,156],add:159,advanc:12,algorithm:167,align:96,allow:[155,156],amcl:[85,154],analog:2,angl:[96,156],api:[27,154,155],appli:155,approach:154,architectur:151,areerrorcodespres:58,assist:[1,2,154],assistedteleop:[30,86],attribut:153,automat:179,backtrac:179,backup:[31,86,153],baseobstaclecrit:133,becom:25,behavior:[18,19,28,86,87,88,152,153,154,155,156,158,159,165,174,181,188],being:154,benchmark:155,binari:[108,144],bond:28,both:155,brand:8,bringup:[156,179,180],btservicenod:154,build:[143,144,145,168,170,171,173],cach:174,calibr:[26,177],camera:177,cancel:154,cancelassistedteleop:32,cancelbackup:33,cancelcontrol:34,canceldriveonhead:35,cancelspin:36,cancelwait:37,capabl:152,certif:148,chang:[151,153,154,155,156],check:155,checker:[27,153,154,155,165],citat:150,cleararea:154,clearcostmaparoundrobot:[38,153],clearcostmapexceptregion:[39,153],clearentirecostmap:40,click:181,code:[155,156,175],collis:[27,83,84,89,155,156,187],command:[27,154,155],common:[143,171],composit:[154,175],computepaththroughpos:[41,153],computepathtopos:[42,153],concept:28,conclus:[167,168,170,171,172,173,175],condit:[20,88],config:159,configur:[2,13,29,153,167,168,170,171,183,185,187,189],consist:25,constant:154,constrain:[90,154],constraint:96,constructor:155,contact:14,contain:[144,145,146],control:[3,20,28,88,91,93,96,100,117,153,154,155,161,165,167,174,189],controllerselector:43,controllerserv:153,convert:13,corner:154,costmap2d:[92,153,160,186],costmap:[27,28,92,95,96,152,153,155,165,171,183,185,186],costmap_2d_nod:155,costmaplay:154,crash:179,creat:[2,3,145,158,159,161,162,163,181],critic:[93,96,156],current_:153,curv:155,custom:[159,188],dash:151,dco:148,debug:156,deceler:155,decor:[20,88],demo:[27,170,172,187,189],denois:[109,155,178],depend:143,descript:[103,171],detail:19,detect:154,detector:[83,156],determin:11,dev:[145,146],develop:[144,147,148],direction:156,distanc:[154,155],distancecontrol:77,distancetravel:59,distribut:144,docker:144,doxygen:144,driveonhead:[44,86],drop:154,dwb:[93,117,155],dynam:[4,21,154,181],each:152,ecosystem:13,edit:188,eloqu:[151,152],enabl:[160,178,183,185],enumer:156,enviro:182,environ:173,environment:[5,28],error:[155,156,175],estim:28,euclidean:154,exampl:[27,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,86,87,88,90,91,92,93,94,95,96,97,98,99,100,101,102,104,105,106,107,108,109,111,114,130,131,132,149,150,167],except:154,execut:[187,189],executor:[154,165],expand:155,extend:154,extern:186,failur:[143,155],failure_toler:153,familiar:176,featur:[83,84],feedback:[153,155],field:174,file:[155,156,158,161,162,163,170,171,179,180],filter:[28,92,95,108,111,114,152,153,155,165,178,183,185],first:169,fix:154,follow:[21,28,96,107,181],followpath:[45,153],followpoint:152,footprint:[27,168,174],form:28,forward:[96,155],foxi:[152,153],framework:12,from:[155,179,180],galact:[153,154],gazebo:[154,170,171],gener:[96,144,152,190],get:[146,148,149,179,184],give:155,global:28,globallyupdatedgo:60,goal:[23,96,153,154,155,156,165,182],goal_checker_id:153,goalaligncrit:134,goalcheckerselector:46,goaldistcrit:135,goalreach:61,goalupd:62,goalupdat:78,golai:[101,155],gradientlay:160,grid:5,groot:[153,154,188],guid:[29,143,145,147,157,169,174],handl:156,handler:96,help:144,heurist:174,horizon:96,how:[146,178],humbl:[154,155,166],hybrid:131,ignor:154,imag:[144,145,171],improv:[6,154],includ:[154,155],induc:178,inflat:[96,110,174],info:[95,183,185],inform:153,initi:182,initialposereceiv:63,input:[30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,70,71,72,73,75,77,78,79,80,82],inputatwaypoint:127,instal:[144,149,186],integr:[4,10,96,155],interact:188,interfac:[153,184],interpret:180,introduc:156,introduct:[20,168,170,171,172],invalid:[25,154],invert:154,involv:148,iron:[155,156,166],isbatterycharg:64,isbatterychargingcondit:155,isbatterylow:65,ispathvalid:66,isstuck:67,issu:143,iter:118,jazzi:[156,166],keepout:[111,183],kinemat:[119,154],larg:179,laserscan:171,lattic:132,launch:[153,154,155,156,170,171,173,174,179,180,182,184,186],layer:[28,96,109,110,112,115,116,152,155,156,165,178],librari:159,licens:148,lifecycl:[28,94,145,154,175],limit:[154,155,185],limitedaccelgener:121,live:154,load:155,local:[6,28,170,171],locat:182,logic:154,lookahead:155,loop:155,love:174,major:154,make:160,manag:[94,154],map:[5,95,152,155,171,184],map_serv:155,mark:153,mask:[183,185],messag:[152,171],migrat:157,model:[5,96,154,155],modifi:[176,186],monitor:[84,89,154,155,187],more:155,motion:[96,154],move:156,moveit:2,mppi:[96,156],multi:156,multipl:[154,155],multithread:7,name:[155,156,158,159,161,162,163],nav2:[18,20,28,143,150,153,154,155,171,174,175,178,179,180,181,182,183,185,187],nav2_collision_monitor:156,nav2_cor:154,nav2_costmap_2d:171,navfn:[97,153,154],navig:[4,7,8,9,12,17,19,22,23,24,25,28,87,149,152,154,155,163,165,167,182,183,184,185],navigatethroughpos:[47,153],navigatetopos:[48,153],navigation2:[151,172,184,186],node:[9,11,20,28,83,84,88,89,153,154,155,156,165,171,175,176,179,180,188],nois:178,note:96,object:181,observ:[83,84],obstacl:[4,23,96,112,153,156,174,178],obstaclefootprintcrit:136,odometri:[26,28,170],offer:174,offset:96,onli:154,option:[156,174],orient:154,origin:148,oscillationcrit:137,other:[28,174],ouput:[55,56],our:150,output:[31,41,42,43,44,45,46,47,48,49,51,52,53,54],overview:[19,27,28,150,158,159,160,161,162,163,176,177,178,179,180,181,182,183,184,185,186,187,188,189],packag:151,page:174,panel:[153,155],param:[154,156,158,161,162,163],paramet:[59,61,78,83,84,85,86,87,90,91,92,94,95,96,97,98,99,100,101,102,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,153,154,155,156,186],parameteriz:155,particl:152,pass:[158,161,162,163],path:[25,96,154,155,156],pathaligncrit:138,pathdistcrit:139,pathexpiringtim:68,pathlongeronapproach:[79,154],paus:23,photoatwaypoint:128,physic:[173,182],pipelinesequ:[20,74],place:174,planner:[3,28,97,98,103,105,130,131,132,153,154,155,156,159,162,165,167,174],plannerselector:49,plugin:[3,86,88,91,92,93,98,103,107,151,152,153,154,155,156,158,159,160,161,162,163,164,165,167,170,171,174,176,186],point:[21,181],pointcloud2:[153,171],pointcloud:153,polygon:[83,84],port:[5,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,61,70,71,72,73,75,77,78,79,80,82],pose:[19,22,23,24,25,155,182],poseprogresscheck:[123,155],posit:28,potenti:174,predict:[96,155],prefer:96,preferforwardcrit:140,preliminari:[179,180],prepar:[183,185,187],prerequisit:[19,146,170],primari:189,process:[148,154],profil:180,program:0,progress:165,progress_checker_plugin:155,project:[0,15,179],properti:173,provid:[89,91,103,107],prune:155,publish:[120,155,172,173,183,185],pure:[99,161],pursuit:[99,161],python:[154,155],radiu:174,rai:153,rang:[113,171],rate:154,ratecontrol:80,rebuild:145,recoveri:[19,20,28,153,154],recoverynod:75,recurs:155,reduc:[11,154],refactor:154,refin:155,regul:[99,155],regulatedpurepursuitcontrol:153,reinitializegloballoc:50,relat:15,releas:144,remov:[153,154,155],removepassedgo:51,renam:155,replan:[19,25,154],report:143,represent:28,requir:[158,159,160,161,162,163,176,177,178,182,183,184,185,187],respawn:154,result:[154,156,180],revers:155,roadmap:166,robot:[16,154,156,168,169,170,173,174,184],roll:144,rotat:[100,154,174,189],rotatetogoalcrit:141,roundrobin:[20,76],rpp:[154,155],run:[13,149,155,158,159,160,161,162,163,168,170,171,178,181,183,185],rviz:[153,155,168,171,173,181,182,186],safeti:[9,155],save:155,saver:95,savitzki:[101,155],scale:154,secur:146,select:[152,167,174],semant:10,send:182,sensor:[113,171],sensor_msg:[153,171],server:[28,86,90,91,95,98,104,152,154,155,156,167,175,183,185],servic:154,set:[167,168,170,171,172,173],setup:[169,170,181,182,186],shim:[100,154,189],simpl:[27,102,154,155],simplegoalcheck:124,simpleprogresscheck:125,simplif:184,simul:[170,171,181],singletrigg:81,size:96,slam:[28,184],slam_toolbox:171,smac:[103,130,131,132,154,155,156,174],smacplann:153,smacplanner2d:154,smacplannerhybrid:155,small:154,smoother:[28,90,101,102,104,106,154,155,165,176],smootherselector:[53,155],smoothpath:52,sourc:[83,84,144],spawn:154,specif:20,specifi:176,speed:[114,155,185],speedcontrol:82,spin:[54,86],sponsor:150,stabl:155,stack:[178,183,185,187],standard:[28,153],standardtrajectorygener:122,star:105,start:[145,146,149,155,184],state:[28,132,155,173],step:[158,159,160,161,162,163,176,177,178,181,182,183,184,185,186],stoppedgoalcheck:126,straightlin:162,student:0,stvl:186,substitut:156,subtre:19,summari:167,summer:0,support:[153,154],system:170,task:[154,165,175],teleop:[1,154],termin:145,test:[12,155],theta:[105,154],thetastarplann:153,through:[22,158,161,162,163],time:[13,153,155,169],timeexpir:69,timeout:[154,155],toler:155,trace:153,trajectori:[93,96],transform:172,transformavail:70,tree:[18,19,28,87,88,152,153,155,159,165,181,188],troubleshoot:143,truncatepath:55,truncatepathloc:[56,154],tune:174,turtlebot:182,tutori:[158,159,160,161,162,163,164,176,177,178,181,182,183,184,185,186,190],twirl:96,twirlingcrit:142,twist:13,twiststamp:13,type:155,unit:153,updat:[152,153],urdf:[170,171,173],usag:153,use:146,use_final_approach_orient:154,use_sim_tim:155,user:96,using:[170,171,173],variabl:182,veloc:[106,154,155],verif:[168,170,171],visual:[96,168,171,173,188],viz_expans:155,voxel:[116,156],wait:57,waitatwaypoint:129,walkthrough:19,waypoint:[28,107,155,165],websit:8,what:[146,189],when:155,why:146,wisdom:96,word:96,work:[146,152,178,184],wouldacontrollerrecoveryhelp:71,wouldaplannerrecoveryhelp:72,wouldasmootherrecoveryhelp:73,write:[158,159,160,161,162,163,173],xml:[88,153,176],xytheta:118,yaml:155,your:[159,170,176,182],zone:183}}) \ No newline at end of file diff --git a/setup_guides/algorithm/select_algorithm.html b/setup_guides/algorithm/select_algorithm.html index e0ea12f53..12f1c3637 100644 --- a/setup_guides/algorithm/select_algorithm.html +++ b/setup_guides/algorithm/select_algorithm.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/footprint/setup_footprint.html b/setup_guides/footprint/setup_footprint.html index 5db713108..2d85bb758 100644 --- a/setup_guides/footprint/setup_footprint.html +++ b/setup_guides/footprint/setup_footprint.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/index.html b/setup_guides/index.html index bea686690..7e3d62577 100644 --- a/setup_guides/index.html +++ b/setup_guides/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/odom/setup_odom.html b/setup_guides/odom/setup_odom.html index 9c600a76f..4228107d8 100644 --- a/setup_guides/odom/setup_odom.html +++ b/setup_guides/odom/setup_odom.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/sensors/setup_sensors.html b/setup_guides/sensors/setup_sensors.html index e4b8a03c6..b2e5a3d2b 100644 --- a/setup_guides/sensors/setup_sensors.html +++ b/setup_guides/sensors/setup_sensors.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/transformation/setup_transforms.html b/setup_guides/transformation/setup_transforms.html index 955ba5b35..da38622c9 100644 --- a/setup_guides/transformation/setup_transforms.html +++ b/setup_guides/transformation/setup_transforms.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/setup_guides/urdf/setup_urdf.html b/setup_guides/urdf/setup_urdf.html index 87f0334e1..770b394fc 100644 --- a/setup_guides/urdf/setup_urdf.html +++ b/setup_guides/urdf/setup_urdf.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tuning/index.html b/tuning/index.html index b2bbb3734..afd9a8761 100644 --- a/tuning/index.html +++ b/tuning/index.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/adding_a_nav2_task_server.html b/tutorials/docs/adding_a_nav2_task_server.html index b91ffa410..650a21fd1 100644 --- a/tutorials/docs/adding_a_nav2_task_server.html +++ b/tutorials/docs/adding_a_nav2_task_server.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/adding_smoother.html b/tutorials/docs/adding_smoother.html index 9220dca67..50aaccdf4 100644 --- a/tutorials/docs/adding_smoother.html +++ b/tutorials/docs/adding_smoother.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/camera_calibration.html b/tutorials/docs/camera_calibration.html index 82878bd39..0ece3d4b2 100644 --- a/tutorials/docs/camera_calibration.html +++ b/tutorials/docs/camera_calibration.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/filtering_of_noise-induced_obstacles.html b/tutorials/docs/filtering_of_noise-induced_obstacles.html index 685cd665d..7963a40e1 100644 --- a/tutorials/docs/filtering_of_noise-induced_obstacles.html +++ b/tutorials/docs/filtering_of_noise-induced_obstacles.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/get_backtrace.html b/tutorials/docs/get_backtrace.html index d1cab6f53..520667ca5 100644 --- a/tutorials/docs/get_backtrace.html +++ b/tutorials/docs/get_backtrace.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/get_profile.html b/tutorials/docs/get_profile.html index d54e38235..e26f18f55 100644 --- a/tutorials/docs/get_profile.html +++ b/tutorials/docs/get_profile.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_dynamic_point_following.html b/tutorials/docs/navigation2_dynamic_point_following.html index 0d03899a9..a67d784d1 100644 --- a/tutorials/docs/navigation2_dynamic_point_following.html +++ b/tutorials/docs/navigation2_dynamic_point_following.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_on_real_turtlebot3.html b/tutorials/docs/navigation2_on_real_turtlebot3.html index 606f80e26..f529471ce 100644 --- a/tutorials/docs/navigation2_on_real_turtlebot3.html +++ b/tutorials/docs/navigation2_on_real_turtlebot3.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_with_keepout_filter.html b/tutorials/docs/navigation2_with_keepout_filter.html index 4b3c1f073..01a5512aa 100644 --- a/tutorials/docs/navigation2_with_keepout_filter.html +++ b/tutorials/docs/navigation2_with_keepout_filter.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_with_slam.html b/tutorials/docs/navigation2_with_slam.html index 29d8ddc73..5339c0744 100644 --- a/tutorials/docs/navigation2_with_slam.html +++ b/tutorials/docs/navigation2_with_slam.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_with_speed_filter.html b/tutorials/docs/navigation2_with_speed_filter.html index 92261ad81..bc3bbf22f 100644 --- a/tutorials/docs/navigation2_with_speed_filter.html +++ b/tutorials/docs/navigation2_with_speed_filter.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/navigation2_with_stvl.html b/tutorials/docs/navigation2_with_stvl.html index c41e5acc3..3869a868a 100644 --- a/tutorials/docs/navigation2_with_stvl.html +++ b/tutorials/docs/navigation2_with_stvl.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/using_collision_monitor.html b/tutorials/docs/using_collision_monitor.html index 2d95707e6..13e363097 100644 --- a/tutorials/docs/using_collision_monitor.html +++ b/tutorials/docs/using_collision_monitor.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/using_groot.html b/tutorials/docs/using_groot.html index 833f2acaa..460396b93 100644 --- a/tutorials/docs/using_groot.html +++ b/tutorials/docs/using_groot.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/docs/using_shim_controller.html b/tutorials/docs/using_shim_controller.html index 9233b2bc8..9b3a4f57b 100644 --- a/tutorials/docs/using_shim_controller.html +++ b/tutorials/docs/using_shim_controller.html @@ -689,13 +689,11 @@
  • Collision Monitor diff --git a/tutorials/index.html b/tutorials/index.html index 5b19a7786..fdbf25c50 100644 --- a/tutorials/index.html +++ b/tutorials/index.html @@ -689,13 +689,11 @@
  • Collision Monitor