Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
start_pose_orientation_scorer.hpp
1 // Copyright (c) 2025, Polymath Robotics Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__START_POSE_ORIENTATION_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__START_POSE_ORIENTATION_SCORER_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "nav2_util/lifecycle_node.hpp"
22 #include "nav2_core/route_exceptions.hpp"
23 #include "nav2_route/interfaces/edge_cost_function.hpp"
24 #include "nav2_util/line_iterator.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_util/robot_utils.hpp"
27 #include "nav2_costmap_2d/costmap_subscriber.hpp"
28 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
29 #include "tf2/utils.hpp"
30 #include "angles/angles.h"
31 
32 namespace nav2_route
33 {
34 
44 {
45 public:
50 
54  virtual ~StartPoseOrientationScorer() = default;
55 
59  void configure(
60  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
61  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
62  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
63  const std::string & name) override;
64 
72  bool score(
73  const EdgePtr edge, const RouteRequest & route_request,
74  const EdgeType & edge_type, float & cost) override;
75 
80  std::string getName() override;
81 
82 protected:
83  rclcpp::Logger logger_{rclcpp::get_logger("StartPoseOrientationScorer")};
84  std::string name_;
85  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
86  double orientation_tolerance_;
87  float orientation_weight_;
88  bool use_orientation_threshold_;
89 };
90 
91 } // namespace nav2_route
92 
93 #endif // NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__START_POSE_ORIENTATION_SCORER_HPP_
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Scores initial edge by comparing the orientation of the robot's current pose and the orientation of t...
virtual ~StartPoseOrientationScorer()=default
destructor
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
std::string getName() override
Get name of the plugin for parameter scope mapping.
StartPoseOrientationScorer()=default
Constructor.
void configure(const rclcpp_lifecycle::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
An object representing edges between nodes.
Definition: types.hpp:134
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224