Class GoalOrientationScorer

Inheritance Relationships

Base Type

Class Documentation

class GoalOrientationScorer : public 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.

Public Functions

GoalOrientationScorer() = default

Constructor.

virtual ~GoalOrientationScorer() = default

destructor

virtual 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.

virtual bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override

Main scoring plugin API.

Parameters:
  • 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

Returns:

bool if this edge is open valid to traverse

virtual std::string getName() override

Get name of the plugin for parameter scope mapping.

Returns:

Name

Protected Attributes

rclcpp::Logger logger_ = {rclcpp::get_logger("GoalOrientationScorer")}
std::string name_
double orientation_tolerance_
float orientation_weight_
bool use_orientation_threshold_