EasyNav Simple Stack
Loading...
Searching...
No Matches
SimplePlanner.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in short)
4// licensed under the GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6//
7// Easy Navigation program is free software: you can redistribute it and/or modify
8// it under the terms of the GNU General Public License as published by
9// the Free Software Foundation, either version 3 of the License, or
10// (at your option) any later version.
11//
12// This program is distributed in the hope that it will be useful,
13// but WITHOUT ANY WARRANTY; without even the implied warranty of
14// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15// GNU General Public License for more details.
16//
17// You should have received a copy of the GNU General Public License
18// along with this program. If not, see <http://www.gnu.org/licenses/>.
19
22
23#ifndef EASYNAV_PLANNER__SIMPLEPLANNER_HPP_
24#define EASYNAV_PLANNER__SIMPLEPLANNER_HPP_
25
26#include <memory>
27#include <vector>
28
29#include "nav_msgs/msg/path.hpp"
30
31#include "easynav_core/PlannerMethodBase.hpp"
33#include "easynav_common/types/NavState.hpp"
34
35namespace easynav
36{
37
40{
41public:
47 explicit SimplePlanner();
48
57 virtual std::expected<void, std::string> on_initialize() override;
58
67 void update(NavState & nav_state) override;
68
69protected:
72
73 nav_msgs::msg::Path current_path_;
74
76 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_pub_;
77
87 std::vector<geometry_msgs::msg::Pose> a_star_path(
88 const SimpleMap & map,
89 const geometry_msgs::msg::Pose & start,
90 const geometry_msgs::msg::Pose & goal,
91 double resolution);
92
106 const SimpleMap & map,
107 int cx, int cy,
108 double clearance_cells);
109};
110
111} // namespace easynav
112
113#endif // EASYNAV_PLANNER__SIMPLEPLANNER_HPP_
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