20 #include "nav2_route/edge_scorer.hpp"
26 nav2::LifecycleNode::SharedPtr node,
27 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
28 const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber)
29 : plugin_loader_(
"nav2_route",
"nav2_route::EdgeCostFunction")
32 const std::vector<std::string> default_plugin_ids({
"DistanceScorer",
"DynamicEdgesScorer"});
33 const std::vector<std::string> default_plugin_types(
34 {
"nav2_route::DistanceScorer",
"nav2_route::DynamicEdgesScorer"});
36 nav2::declare_parameter_if_not_declared(
37 node,
"edge_cost_functions", rclcpp::ParameterValue(default_plugin_ids));
38 auto edge_cost_function_ids = node->get_parameter(
"edge_cost_functions").as_string_array();
40 if (edge_cost_function_ids == default_plugin_ids) {
41 for (
unsigned int i = 0; i != edge_cost_function_ids.size(); i++) {
42 nav2::declare_parameter_if_not_declared(
43 node, default_plugin_ids[i] +
".plugin", rclcpp::ParameterValue(default_plugin_types[i]));
47 for (
size_t i = 0; i != edge_cost_function_ids.size(); i++) {
49 std::string type = nav2::get_plugin_type_param(
50 node, edge_cost_function_ids[i]);
51 EdgeCostFunction::Ptr scorer = plugin_loader_.createUniqueInstance(type);
53 node->get_logger(),
"Created edge cost function plugin %s of type %s",
54 edge_cost_function_ids[i].c_str(), type.c_str());
55 scorer->configure(node, tf_buffer, costmap_subscriber, edge_cost_function_ids[i]);
56 plugins_.push_back(std::move(scorer));
57 }
catch (
const pluginlib::PluginlibException & ex) {
60 "Failed to create edge cost function. Exception: %s", ex.what());
68 const EdgeType & edge_type,
float & total_score)
71 float curr_score = 0.0;
73 for (
auto & plugin : plugins_) {
77 for (
auto & plugin : plugins_) {
79 if (plugin->score(edge, route_request, edge_type, curr_score)) {
80 total_score += curr_score;
91 return plugins_.size();
int numPlugins() const
Provide the number of plugisn in the scorer loaded.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &score)
Score the edge with the set of plugins.
EdgeScorer(nav2::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
Constructor.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...