Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
goal_orientation_scorer.cpp
1 // Copyright (c) 2024, 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 #include <memory>
16 #include <string>
17 
18 #include "nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp"
19 
20 namespace nav2_route
21 {
22 
24  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
25  const std::shared_ptr<tf2_ros::Buffer>/* tf_buffer */,
26  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>/* costmap_subscriber */,
27  const std::string & name)
28 {
29  RCLCPP_INFO(node->get_logger(), "Configuring goal orientation scorer.");
30  name_ = name;
31  logger_ = node->get_logger();
32 
33  nav2_util::declare_parameter_if_not_declared(
34  node, getName() + ".orientation_tolerance", rclcpp::ParameterValue(M_PI / 2.0));
35 
36  nav2_util::declare_parameter_if_not_declared(
37  node, getName() + ".orientation_weight", rclcpp::ParameterValue(1.0));
38 
39  nav2_util::declare_parameter_if_not_declared(
40  node, getName() + ".use_orientation_threshold", rclcpp::ParameterValue(false));
41 
42  orientation_tolerance_ = node->get_parameter(getName() + ".orientation_tolerance").as_double();
43  orientation_weight_ =
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();
47 }
48 
50  const EdgePtr edge,
51  const RouteRequest & route_request,
52  const EdgeType & edge_type, float & cost)
53 {
54  if (!route_request.use_poses) {
56  "Cannot use goal orientation scorer without goal pose specified!");
57  }
58 
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));
65 
66  if (use_orientation_threshold_) {
67  if (d_yaw > orientation_tolerance_) {
68  return false;
69  }
70  }
71 
72  cost = orientation_weight_ * static_cast<float>(d_yaw);
73  }
74  return true;
75 }
76 
78 {
79  return name_;
80 }
81 
82 } // namespace nav2_route
83 
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 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.
std::string getName() override
Get name of the plugin for parameter scope mapping.
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