Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::GoalOrientationScorer Class Reference

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>

Inheritance diagram for nav2_route::GoalOrientationScorer:
Inheritance graph
[legend]
Collaboration diagram for nav2_route::GoalOrientationScorer:
Collaboration graph
[legend]

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...
 
- Public Member Functions inherited from nav2_route::EdgeCostFunction
 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

- Public Types inherited from nav2_route::EdgeCostFunction
using Ptr = std::shared_ptr< nav2_route::EdgeCostFunction >
 

Detailed Description

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.

Member Function Documentation

◆ getName()

std::string nav2_route::GoalOrientationScorer::getName ( )
overridevirtual

Get name of the plugin for parameter scope mapping.

Returns
Name

Implements nav2_route::EdgeCostFunction.

Definition at line 77 of file goal_orientation_scorer.cpp.

Referenced by configure().

Here is the caller graph for this function:

◆ score()

bool nav2_route::GoalOrientationScorer::score ( const EdgePtr  edge,
const RouteRequest route_request,
const EdgeType &  edge_type,
float &  cost 
)
overridevirtual

Main scoring plugin API.

Parameters
edgeThe edge pointer to score, which has access to the start/end nodes and their associated metadata and actions
costof the edge scored
Returns
bool if this edge is open valid to traverse

Implements nav2_route::EdgeCostFunction.

Definition at line 49 of file goal_orientation_scorer.cpp.


The documentation for this class was generated from the following files: