23#ifndef EASYNAV_PLANNER__SIMPLEPLANNER_HPP_
24#define EASYNAV_PLANNER__SIMPLEPLANNER_HPP_
29#include "nav_msgs/msg/path.hpp"
31#include "easynav_core/PlannerMethodBase.hpp"
33#include "easynav_common/types/NavState.hpp"
57 virtual std::expected<void, std::string>
on_initialize()
override;
67 void update(NavState & nav_state)
override;
76 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr
path_pub_;
89 const geometry_msgs::msg::Pose & start,
90 const geometry_msgs::msg::Pose & goal,
108 double clearance_cells);
Declaration of the SimpleMap type.
Simple 2D uint8_t grid using basic C++ types, with full metric conversion support.
Definition SimpleMap.hpp:46
void update(NavState &nav_state) override
Updates the planner by computing a new path.
Definition SimplePlanner.cpp:106
bool isFreeWithClearance(const SimpleMap &map, int cx, int cy, double clearance_cells)
Checks whether a map cell is free, considering a clearance area.
Definition SimplePlanner.cpp:178
double robot_radius_
Radius of the robot used for collision checking.
Definition SimplePlanner.hpp:70
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.
Definition SimplePlanner.cpp:201
SimplePlanner()
Default constructor.
Definition SimplePlanner.cpp:76
nav_msgs::msg::Path current_path_
The last computed path.
Definition SimplePlanner.hpp:73
virtual std::expected< void, std::string > on_initialize() override
Initializes the planner.
Definition SimplePlanner.cpp:90
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr path_pub_
Publisher for the computed navigation path.
Definition SimplePlanner.hpp:76
double clearance_distance_
Minimum clearance distance from obstacles in meters.
Definition SimplePlanner.hpp:71
Definition SimpleMap.hpp:37