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_
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"
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;
74 const EdgeType & edge_type,
float & cost)
override;
83 rclcpp::Logger logger_{rclcpp::get_logger(
"StartPoseOrientationScorer")};
85 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
86 double orientation_tolerance_;
87 float orientation_weight_;
88 bool use_orientation_threshold_;
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.
An object to store salient features of the route request including its start and goal node ids,...