Class StartPoseOrientationScorer

Inheritance Relationships

Base Type

Class Documentation

class StartPoseOrientationScorer : public nav2_route::EdgeCostFunction

Scores initial edge by comparing the orientation of the robot’s current 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

StartPoseOrientationScorer() = default

Constructor.

virtual ~StartPoseOrientationScorer() = 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("StartPoseOrientationScorer")}
std::string name_
std::shared_ptr<tf2_ros::Buffer> tf_buffer_
double orientation_tolerance_
float orientation_weight_
bool use_orientation_threshold_