23#ifndef EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
24#define EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
29#include "nav_msgs/msg/path.hpp"
31#include "easynav_core/PlannerMethodBase.hpp"
33#include "easynav_common/types/NavState.hpp"
60 virtual std::expected<void, std::string>
on_initialize()
override;
69 void update(NavState & nav_state)
override;
80 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr
path_pub_;
99 const geometry_msgs::msg::Pose & start,
100 const geometry_msgs::msg::Pose & goal);
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition costmap_2d.hpp:69
void update(NavState &nav_state) override
Executes a planning cycle using the current navigation state.
Definition CostmapPlanner.cpp:101
double cost_axial_
Cost multiplier for axial (horizontal/vertical) moves.
Definition CostmapPlanner.hpp:74
CostmapPlanner()
Default constructor.
Definition CostmapPlanner.cpp:72
double cost_factor_
Scaling factor applied to cell cost values.
Definition CostmapPlanner.hpp:72
nav_msgs::msg::Path current_path_
Most recently computed path.
Definition CostmapPlanner.hpp:77
virtual std::expected< void, std::string > on_initialize() override
Initializes the planner.
Definition CostmapPlanner.cpp:83
double cost_diagonal_
Cost multiplier for diagonal moves.
Definition CostmapPlanner.hpp:75
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr path_pub_
Publisher for the computed navigation path (for visualization or monitoring).
Definition CostmapPlanner.hpp:80
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.
Definition CostmapPlanner.cpp:149
double inflation_penalty_
Extra cost penalty for paths near inflated obstacles.
Definition CostmapPlanner.hpp:73
Provides a mapping for often used cost values.
Definition cost_values.hpp:41