Class DynamicEdgesScorer

Inheritance Relationships

Base Type

Class Documentation

class DynamicEdgesScorer : public nav2_route::EdgeCostFunction

Rejects edges that are in the closed set of edges for navigation to prevent routes from containing paths blocked or otherwise deemed not currently traversable.

Public Functions

DynamicEdgesScorer() = default

Constructor.

virtual ~DynamicEdgesScorer() = 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

void closedEdgesCb(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<nav2_msgs::srv::DynamicEdges::Request> request, std::shared_ptr<nav2_msgs::srv::DynamicEdges::Response> response)

Service callback to process edge changes.

Parameters:
  • request – Service request containing newly closed edges or opened edges

  • response – Response to service (empty)

Protected Attributes

rclcpp::Logger logger_ = {rclcpp::get_logger("DynamicEdgesScorer")}
std::string name_
std::set<unsigned int> closed_edges_
std::unordered_map<unsigned int, float> dynamic_penalties_
rclcpp::Service<nav2_msgs::srv::DynamicEdges>::SharedPtr service_