[Documentation] [TitleIndex] [WordIndex

Package Summary

A simple planner that attempts to keep the robot close to a line between the starting and target goal.

Simple Projecting Line Planner

A local planner that takes two goals (last and next), and follows a projected goal that keeps it close to the line segment between the two goals. Designed to resist strong side forces, such as from wind or water current.

https://github.com/MoffKalast/line_planner/raw/noetic-devel/docs/demo.gif

Params

Note that min speed should be less or equal to max speed.

   1 <node name="line_planner" pkg="line_planner" type="line_planner_node.py" output="screen">
   2 
   3     <param name="publish_debug_markers" value="true"/>
   4 
   5     <param name="max_turning_velocity" value="0.9"/>
   6     <param name="max_linear_velocity" value="0.45"/>
   7 
   8     <!-- If base_link is this far away from the line, the projected distance will be min and scale to max when it's on the line.-->
   9     <param name="max_line_divergence" value="1.0"/>
  10 
  11     <param name="min_project_dist" value="0.15"/>
  12     <param name="max_project_dist" value="1.2"/>
  13 
  14     <!-- Distance at which the goal is considered reached.-->
  15     <param name="goal_distance_threshold" value="0.6"/>
  16 
  17     <!-- PID params for heading control.-->
  18     <param name="P" value="3.0"/>
  19     <param name="I" value="0.001"/>
  20     <param name="D" value="65.0"/>
  21 
  22     <!-- Update rate, should be about the same as localization rate.-->
  23     <param name="rate" value="30"/>
  24 
  25     <!-- If we make no or negative progress for this long, the goal is aborted. (seconds)-->
  26     <param name="abort_timeout" value="30.0"/>
  27 
  28 </node>

Here's a diagram showing the possible states of the planner, and which distances each parameter affects:

https://github.com/MoffKalast/line_planner/raw/noetic-devel/docs/diagram.png

Subscribed Topics

Published Topics

Dynamic Reconfigure Params


Bounding Box to Path Helper

This package also contains a small helper demo node that takes a rectangle defined as a PolygonStamped and turns it into various patterns which then get published as a Path that the line planer can execute. Right now it provides three different patterns: lawnmower, expanding square, and victor sierra.

The lawnmower pattern creates a path in a back-and-forth, or "mowing the lawn" manner. The expanding square pattern creates a square outward spiral path. The victor sierra pattern is a coast guard sector search.

It also accepts a home polygon, which it uses to add a final waypoint that points back home after following the path, so the robot doesn't get stuck out of wifi range.

Params

   1 <node name="area_to_path_node" pkg="line_planner" type="area_to_path_node.py" output="screen">
   2     <param name="step_size" value="2.0"/> <!-- determines the distance between parallel lines -->
   3 </node>

Subscribed Topics

Published Topics


2024-04-20 12:47