EasyNav Costmap Stack
Loading...
Searching...
No Matches
CostmapPlanner.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_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
24#define EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_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
43{
44public:
50 explicit CostmapPlanner();
51
60 virtual std::expected<void, std::string> on_initialize() override;
61
69 void update(NavState & nav_state) override;
70
71protected:
72 double cost_factor_;
74 double cost_axial_;
76
77 nav_msgs::msg::Path current_path_;
78
80 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_pub_;
81
97 std::vector<geometry_msgs::msg::Pose> a_star_path(
98 const Costmap2D & map,
99 const geometry_msgs::msg::Pose & start,
100 const geometry_msgs::msg::Pose & goal);
101};
102
103} // namespace easynav
104
105#endif // EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
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