Path Planning
path_planning.py
Overview
path_planning.py is a skeleton global planner that emits a single dummy waypoint at 1 Hz. It lets downstream local planners, controllers and visualisers run before the real global planner is available.
Interfaces (strongly-typed, stateless)
Direction |
Topic |
Message type / Notes |
---|---|---|
Required |
|
|
Required |
|
|
Provided |
|
|
Contract
Pre-conditions
Messages published on /map and /odom_slam share the same frame.
Both topics must have published at least once before planning.
Post-conditions
Every second, exactly one nav_msgs/Path is published.
Path header uses the map’s frame_id and current time stamp.
A single PoseStamped goal at coordinates (1.0, 1.0) is appended.
Invariants
Planner does not block; if data is missing it waits silently.
Orientation of the goal pose remains the default identity quaternion.
Implementation notes
Use rospy.Rate(1) to enforce 1 Hz.
queue_size=1 on the publisher to always keep the latest plan.
Replace plan_path() with a full search algorithm when ready.
- class path_planning.PathPlanner[source]
Bases:
object
Skeleton path planner that publishes a one-step plan each second.
Variables
- map_msgnav_msgs.msg.OccupancyGrid | None
Latest map message.
- odom_msgnav_msgs.msg.Odometry | None
Latest odometry message.
- path_pubrospy.Publisher
Publisher for /planned_path.
Read robot_id from CLI.
Initialise ROS node <robot>_path_planning_node.
Subscribe to /map and /odom_slam.
Advertise /planned_path with queue_size=1.
- map_callback(msg: nav_msgs.msg.OccupancyGrid) None [source]
Store the latest occupancy grid.
- Parameters:
msg (nav_msgs.msg.OccupancyGrid) – Static or SLAM-produced map.
- odom_callback(msg: nav_msgs.msg.Odometry) None [source]
Store the latest odometry.
- Parameters:
msg (nav_msgs.msg.Odometry) – Robot pose in the map frame.
- plan_path() None [source]
Publish a one-step Path when both map and odometry are available.
Preconditions
self.map_msg and self.odom_msg are not None.
Workflow
Create a nav_msgs/Path, stamp it with rospy.Time.now() and set frame_id to self.map_msg.header.frame_id.
Create a geometry_msgs/PoseStamped at (1.0, 1.0) in the map frame.
Append the pose to path.poses.
Publish on /planned_path and log at INFO level.