Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Scores an edge leading to the goal node by comparing the orientation of the route pose and the orientation of the edge by multiplying the deviation from the desired orientation with a user defined weight. An alternative method can be selected, with the use_orientation_threshold flag, which rejects the edge it is greater than some tolerance. More...
#include <nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp>
Public Member Functions | |
GoalOrientationScorer ()=default | |
Constructor. | |
virtual | ~GoalOrientationScorer ()=default |
destructor | |
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. | |
bool | score (const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override |
Main scoring plugin API. More... | |
std::string | getName () override |
Get name of the plugin for parameter scope mapping. More... | |
![]() | |
EdgeCostFunction ()=default | |
Constructor. | |
virtual | ~EdgeCostFunction ()=default |
Virtual destructor. | |
virtual void | prepare () |
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests, or otherwise prepare for scoring. | |
Protected Attributes | |
rclcpp::Logger | logger_ {rclcpp::get_logger("GoalOrientationScorer")} |
std::string | name_ |
double | orientation_tolerance_ |
float | orientation_weight_ |
bool | use_orientation_threshold_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< nav2_route::EdgeCostFunction > |
Scores an edge leading to the goal node by comparing the orientation of the route pose and the orientation of the edge by multiplying the deviation from the desired orientation with a user defined weight. An alternative method can be selected, with the use_orientation_threshold flag, which rejects the edge it is greater than some tolerance.
Definition at line 42 of file goal_orientation_scorer.hpp.
|
overridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::EdgeCostFunction.
Definition at line 77 of file goal_orientation_scorer.cpp.
Referenced by configure().
|
overridevirtual |
Main scoring plugin API.
edge | The edge pointer to score, which has access to the start/end nodes and their associated metadata and actions |
cost | of the edge scored |
Implements nav2_route::EdgeCostFunction.
Definition at line 49 of file goal_orientation_scorer.cpp.