18 #include "nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp"
24 const nav2::LifecycleNode::SharedPtr node,
25 const std::shared_ptr<tf2_ros::Buffer>,
26 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
27 const std::string & name)
29 RCLCPP_INFO(node->get_logger(),
"Configuring goal orientation scorer.");
31 logger_ = node->get_logger();
33 nav2::declare_parameter_if_not_declared(
34 node,
getName() +
".orientation_tolerance", rclcpp::ParameterValue(M_PI / 2.0));
36 nav2::declare_parameter_if_not_declared(
37 node,
getName() +
".orientation_weight", rclcpp::ParameterValue(1.0));
39 nav2::declare_parameter_if_not_declared(
40 node,
getName() +
".use_orientation_threshold", rclcpp::ParameterValue(
false));
42 orientation_tolerance_ = node->get_parameter(
getName() +
".orientation_tolerance").as_double();
44 static_cast<float>(node->get_parameter(
getName() +
".orientation_weight").as_double());
45 use_orientation_threshold_ =
46 node->get_parameter(
getName() +
".use_orientation_threshold").as_bool();
52 const EdgeType & edge_type,
float & cost)
54 if (!route_request.use_poses) {
56 "Cannot use goal orientation scorer without goal pose specified!");
59 if (edge_type == EdgeType::END) {
60 double edge_orientation = std::atan2(
61 edge->end->coords.y - edge->start->coords.y,
62 edge->end->coords.x - edge->start->coords.x);
63 double goal_orientation = tf2::getYaw(route_request.goal_pose.pose.orientation);
64 double d_yaw = std::abs(angles::shortest_angular_distance(edge_orientation, goal_orientation));
66 if (use_orientation_threshold_) {
67 if (d_yaw > orientation_tolerance_) {
72 cost = orientation_weight_ *
static_cast<float>(d_yaw);
84 #include "pluginlib/class_list_macros.hpp"
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Scores an edge leading to the goal node by comparing the orientation of the route pose and the orient...
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
void configure(const nav2::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.
std::string getName() override
Get name of the plugin for parameter scope mapping.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...