Public Member Functions | |
| def | __init__ |
| def | calculate_headings |
| def | distance |
| def | field_callback |
| def | get_next_waypoint_index |
| def | odom_callback |
| def | plan_path |
| def | setup_path_following |
| def | step_path_following |
| def | visualize_path |
| def | visualize_path_as_marker |
| def | visualize_path_as_path |
Public Attributes | |
| clear_costmaps | |
| current_destination | |
| current_distance | |
| cut_spacing | |
| field_frame_id | |
| field_shape | |
| goal_state | |
| just_reset | |
| move_base_client | |
| path | |
| path_marker_pub | |
| path_markers | |
| path_status | |
| previous_destination | |
| robot_pose | |
| start_path_following | |
| testing | |
| timeout | |
This is a ROS node that is responsible for planning and executing the a path through the field.
Definition at line 47 of file path_planner.py.
| def path_planner.PathPlannerNode.__init__ | ( | self | ) |
Definition at line 52 of file path_planner.py.
| def path_planner.PathPlannerNode.calculate_headings | ( | self, | |
| path | |||
| ) |
Calculates the headings between paths and adds them to the waypoints.
Definition at line 157 of file path_planner.py.
| def path_planner.PathPlannerNode.distance | ( | self, | |
| p1, | |||
| p2 | |||
| ) |
Returns the distance between two points.
Definition at line 358 of file path_planner.py.
| def path_planner.PathPlannerNode.field_callback | ( | self, | |
| msg | |||
| ) |
Handles new field polygons, has to be called at least once before planning happens.
Definition at line 100 of file path_planner.py.
Figures out what the index of the next waypoint is. Iterates through the path_status's and finds the visiting one, or the next not_visited one if not visiting on exists.
Definition at line 341 of file path_planner.py.
| def path_planner.PathPlannerNode.odom_callback | ( | self, | |
| msg | |||
| ) |
Watches for the robot's Odometry data, which is used in the path planning as the initial robot position.
Definition at line 113 of file path_planner.py.
| def path_planner.PathPlannerNode.plan_path | ( | self, | |
| field_polygon, | |||
origin = None, |
|||
degrees = 0 |
|||
| ) |
This is called after a field polygon has been received. This uses the automow_planning.coverage module to plan a coverage path using the field geometry. The path consists of a series of waypoints.
Definition at line 120 of file path_planner.py.
| def path_planner.PathPlannerNode.setup_path_following | ( | self, | |
degrees = 0 |
|||
| ) |
Sets up the node for following the planned path. Will wait until the initial robot pose is set and until the move_base actionlib service is available.
Definition at line 292 of file path_planner.py.
| def path_planner.PathPlannerNode.step_path_following | ( | self | ) |
Steps the path following system, checking if new waypoints should be sent, if a timeout has occurred, or if path following needs to be paused.
Definition at line 365 of file path_planner.py.
| def path_planner.PathPlannerNode.visualize_path | ( | self, | |
| path, | |||
path_status = None |
|||
| ) |
Convenience function, calls both visualize_path{as_path, as_marker}
Definition at line 176 of file path_planner.py.
| def path_planner.PathPlannerNode.visualize_path_as_marker | ( | self, | |
| path, | |||
| path_status | |||
| ) |
Publishes visualization Markers to represent the planned path. Publishes the path as a series of spheres connected by lines. The color of the spheres is set by the path_status parameter, which is a list of strings of which the possible values are in ['not_visited', 'visiting', 'visited'].
Definition at line 216 of file path_planner.py.
| def path_planner.PathPlannerNode.visualize_path_as_path | ( | self, | |
| path, | |||
path_status = None |
|||
| ) |
Publishes a nav_msgs/Path msg containing the planned path. If path_status is not None then the only waypoints put in the nav_msgs/Path msg will be ones that are 'not_visited' or 'visiting'.
Definition at line 184 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 297 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.
Definition at line 52 of file path_planner.py.