A planner implementing the A* algorithm on a SimpleMap grid.
More...
#include <SimplePlanner.hpp>
|
| virtual void | on_initialize () override |
| | Initializes the planner.
|
| | SimplePlanner () |
| | Default constructor.
|
| void | update (NavState &nav_state) override |
| | Updates the planner by computing a new path.
|
|
| std::vector< geometry_msgs::msg::Pose > | a_star_path (const SimpleMap &map, const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double resolution) |
| | Runs the A* algorithm to compute a path.
|
| bool | isFreeWithClearance (const SimpleMap &map, int cx, int cy, double clearance_cells) |
| | Checks whether a map cell is free, considering a clearance area.
|
|
| double | clearance_distance_ |
| | Minimum clearance distance from obstacles in meters.
|
| nav_msgs::msg::Path | current_path_ |
| | The last computed path.
|
| rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr | path_pub_ |
| | Publisher for the computed navigation path.
|
| double | robot_radius_ |
| | Radius of the robot used for collision checking.
|
A planner implementing the A* algorithm on a SimpleMap grid.
◆ SimplePlanner()
Default constructor.
Initializes the internal variables and parameters of the planner.
◆ a_star_path()
| std::vector< geometry_msgs::msg::Pose > a_star_path |
( |
const SimpleMap & | map, |
|
|
const geometry_msgs::msg::Pose & | start, |
|
|
const geometry_msgs::msg::Pose & | goal, |
|
|
double | resolution ) |
|
protected |
Runs the A* algorithm to compute a path.
- Parameters
-
| map | The occupancy map used for path planning. |
| start | The starting pose in world coordinates. |
| goal | The target pose in world coordinates. |
| resolution | The cell resolution of the map (in meters). |
- Returns
- A sequence of poses representing the planned path.
◆ isFreeWithClearance()
| bool isFreeWithClearance |
( |
const SimpleMap & | map, |
|
|
int | cx, |
|
|
int | cy, |
|
|
double | clearance_cells ) |
|
protected |
Checks whether a map cell is free, considering a clearance area.
This function verifies if a cell and its surrounding cells (within the specified clearance radius) are free of obstacles.
- Parameters
-
| map | The occupancy map to query. |
| cx | The x-coordinate of the cell. |
| cy | The y-coordinate of the cell. |
| clearance_cells | The clearance radius expressed in number of cells. |
- Returns
- true if the cell and its clearance area are free, false otherwise.
◆ on_initialize()
Initializes the planner.
Configures publishers, retrieves parameters, and prepares the planner for path generation using the available map data.
- Exceptions
-
| std::runtime_error | if initialization fails. |
◆ update()
| void update |
( |
NavState & | nav_state | ) |
|
|
override |
Updates the planner by computing a new path.
Uses the current navigation state (including the robot's position and goal) to generate a path based on the A* algorithm.
- Parameters
-
| nav_state | The current navigation state (contains odometry and goal information). |
◆ clearance_distance_
| double clearance_distance_ |
|
protected |
Minimum clearance distance from obstacles in meters.
◆ current_path_
| nav_msgs::msg::Path current_path_ |
|
protected |
◆ path_pub_
| rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_pub_ |
|
protected |
Publisher for the computed navigation path.
◆ robot_radius_
Radius of the robot used for collision checking.
The documentation for this class was generated from the following files: