EasyNav Plugins
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 Apache License, Version 2.0 (the "License");
5// you may not use this file except in compliance with the License.
6// You may obtain a copy of the License at
7//
8// http://www.apache.org/licenses/LICENSE-2.0
9//
10// Unless required by applicable law or agreed to in writing, software
11// distributed under the License is distributed on an "AS IS" BASIS,
12// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13// See the License for the specific language governing permissions and
14// limitations under the License.
15
18
19#ifndef EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
20#define EASYNAV_COSTMAP_PLANNER__COSTMAPPLANNER_HPP_
21
22#include <vector>
23
24#include "nav_msgs/msg/path.hpp"
25
26#include "easynav_core/PlannerMethodBase.hpp"
28#include "easynav_common/types/NavState.hpp"
29
30namespace easynav
31{
32
38{
39public:
45 explicit CostmapPlanner();
46
55 virtual void on_initialize() override;
56
64 void update(NavState & nav_state) override;
65
66protected:
67 double cost_factor_;
69 double heuristic_scale_ {1.0};
70 bool continuous_replan_ {true};
71 nav_msgs::msg::Path current_path_;
72 geometry_msgs::msg::Pose current_goal_;
73
75 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_pub_;
76
92 std::vector<geometry_msgs::msg::Pose> a_star_path(
93 const Costmap2D & map,
94 const geometry_msgs::msg::Pose & start,
95 const geometry_msgs::msg::Pose & goal);
96};
97
98} // namespace easynav
99
100#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:66
void update(NavState &nav_state) override
Executes a planning cycle using the current navigation state.
Definition CostmapPlanner.cpp:141
bool continuous_replan_
Wheter replan path at freq time.
Definition CostmapPlanner.hpp:70
CostmapPlanner()
Default constructor.
Definition CostmapPlanner.cpp:111
double heuristic_scale_
Scaling factor applied to the heuristic term in A*.
Definition CostmapPlanner.hpp:69
double cost_factor_
Scaling factor applied to cell cost values.
Definition CostmapPlanner.hpp:67
nav_msgs::msg::Path current_path_
Most recently computed path.
Definition CostmapPlanner.hpp:71
geometry_msgs::msg::Pose current_goal_
Current goal.
Definition CostmapPlanner.hpp:72
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr path_pub_
Publisher for the computed navigation path (for visualization or monitoring).
Definition CostmapPlanner.hpp:75
virtual void on_initialize() override
Initializes the planner.
Definition CostmapPlanner.cpp:123
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:256
double inflation_penalty_
Extra cost penalty for paths near inflated obstacles.
Definition CostmapPlanner.hpp:68
Provides a mapping for often used cost values.
Definition cost_values.hpp:41