A planner implementing the A* algorithm on a Costmap2D grid.
More...
#include <CostmapPlanner.hpp>
|
| | CostmapPlanner () |
| | Default constructor.
|
| |
| virtual std::expected< void, std::string > | on_initialize () override |
| | Initializes the planner.
|
| |
| void | update (NavState &nav_state) override |
| | Executes a planning cycle using the current navigation state.
|
| |
|
| std::vector< geometry_msgs::msg::Pose > | a_star_path (const Costmap2D &map, const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal) |
| | Internal A* path planning routine.
|
| |
|
| bool | continuous_replan_ {true} |
| | Wheter replan path at freq time.
|
| |
| double | cost_axial_ |
| | Cost multiplier for axial (horizontal/vertical) moves.
|
| |
| double | cost_diagonal_ |
| | Cost multiplier for diagonal moves.
|
| |
| double | cost_factor_ |
| | Scaling factor applied to cell cost values.
|
| |
| geometry_msgs::msg::Pose | current_goal_ |
| | Current goal.
|
| |
| nav_msgs::msg::Path | current_path_ |
| | Most recently computed path.
|
| |
| double | inflation_penalty_ |
| | Extra cost penalty for paths near inflated obstacles.
|
| |
| rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr | path_pub_ |
| | Publisher for the computed navigation path (for visualization or monitoring).
|
| |
A planner implementing the A* algorithm on a Costmap2D grid.
This class generates a collision-free path using A* search over a 2D costmap. It supports cost-based penalties and anisotropic movement costs.
◆ CostmapPlanner()
Default constructor.
Initializes internal parameters and configuration values.
◆ a_star_path()
| std::vector< geometry_msgs::msg::Pose > a_star_path |
( |
const Costmap2D & | map, |
|
|
const geometry_msgs::msg::Pose & | start, |
|
|
const geometry_msgs::msg::Pose & | goal ) |
|
protected |
Internal A* path planning routine.
Computes a path on the given costmap from the start pose to the goal pose.
Movement cost is influenced by:
- The cost of each cell (retrieved from the costmap).
- Additional inflation penalties near obstacles.
- Anisotropic weights for axial vs diagonal movement.
- Parameters
-
| map | The costmap to plan over. |
| start | The robot's starting pose in world coordinates. |
| goal | The goal pose in world coordinates. |
- Returns
- A vector of poses representing the planned path.
◆ on_initialize()
| std::expected< void, std::string > on_initialize |
( |
| ) |
|
|
overridevirtual |
Initializes the planner.
Loads planner parameters, sets up ROS publishers, and prepares the costmap-based planning environment.
- Returns
- std::expected<void, std::string> A success indicator or error message.
◆ update()
| void update |
( |
NavState & | nav_state | ) |
|
|
override |
Executes a planning cycle using the current navigation state.
Computes a path from the robot's current pose to the goal using A*.
- Parameters
-
| nav_state | Current shared navigation state (input/output). |
◆ continuous_replan_
| bool continuous_replan_ {true} |
|
protected |
Wheter replan path at freq time.
◆ cost_axial_
Cost multiplier for axial (horizontal/vertical) moves.
◆ cost_diagonal_
Cost multiplier for diagonal moves.
◆ cost_factor_
Scaling factor applied to cell cost values.
◆ current_goal_
| geometry_msgs::msg::Pose current_goal_ |
|
protected |
◆ current_path_
| nav_msgs::msg::Path current_path_ |
|
protected |
Most recently computed path.
◆ inflation_penalty_
| double inflation_penalty_ |
|
protected |
Extra cost penalty for paths near inflated obstacles.
◆ path_pub_
| rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_pub_ |
|
protected |
Publisher for the computed navigation path (for visualization or monitoring).
The documentation for this class was generated from the following files: