Class SemanticScorer

Inheritance Relationships

Base Type

Class Documentation

class SemanticScorer : public nav2_route::EdgeCostFunction

Scores an edge based on arbitrary graph semantic data such as set priority/danger levels or regional attributes (e.g. living room, bathroom, work cell 2)

Public Functions

SemanticScorer() = default

Constructor.

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

void metadataValueScorer(Metadata &mdata, float &score)

Scores graph object based on metadata’s semantic value at key.

Parameters:
  • mdataMetadata

  • score – to add to

void metadataKeyScorer(Metadata &mdata, float &score)

Scores graph object based on metadata’s key values.

Parameters:
  • mdataMetadata

  • score – to add to

virtual std::string getName() override

Get name of the plugin for parameter scope mapping.

Returns:

Name

Protected Attributes

std::string name_
std::string key_
std::unordered_map<std::string, float> semantic_info_
float weight_