18 #include "nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp"
24 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
25 const std::shared_ptr<tf2_ros::Buffer>,
26 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
27 const std::string & name)
29 RCLCPP_INFO(node->get_logger(),
"Configuring costmap scorer.");
31 logger_ = node->get_logger();
32 clock_ = node->get_clock();
35 nav2_util::declare_parameter_if_not_declared(
36 node,
getName() +
".use_maximum", rclcpp::ParameterValue(
true));
37 use_max_ =
static_cast<float>(node->get_parameter(
getName() +
".use_maximum").as_bool());
40 nav2_util::declare_parameter_if_not_declared(
41 node,
getName() +
".invalid_on_collision", rclcpp::ParameterValue(
true));
42 invalid_on_collision_ =
43 static_cast<float>(node->get_parameter(
getName() +
".invalid_on_collision").as_bool());
46 nav2_util::declare_parameter_if_not_declared(
47 node,
getName() +
".invalid_off_map", rclcpp::ParameterValue(
true));
49 static_cast<float>(node->get_parameter(
getName() +
".invalid_off_map").as_bool());
52 nav2_util::declare_parameter_if_not_declared(
53 node,
getName() +
".max_cost", rclcpp::ParameterValue(253.0));
54 max_cost_ =
static_cast<float>(node->get_parameter(
getName() +
".max_cost").as_double());
57 nav2_util::declare_parameter_if_not_declared(
58 node,
getName() +
".check_resolution", rclcpp::ParameterValue(2));
59 check_resolution_ =
static_cast<unsigned int>(
60 node->get_parameter(
getName() +
".check_resolution").as_int());
63 std::string server_costmap_topic = node->get_parameter(
"costmap_topic").as_string();
64 nav2_util::declare_parameter_if_not_declared(
65 node,
getName() +
".costmap_topic",
66 rclcpp::ParameterValue(std::string(
"global_costmap/costmap_raw")));
67 std::string costmap_topic =
68 node->get_parameter(
getName() +
".costmap_topic").as_string();
69 if (costmap_topic != server_costmap_topic) {
70 costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
74 "Using costmap topic: %s instead of server costmap topic: %s for CostmapScorer.",
75 costmap_topic.c_str(), server_costmap_topic.c_str());
77 costmap_subscriber_ = costmap_subscriber;
81 nav2_util::declare_parameter_if_not_declared(
82 node,
getName() +
".weight", rclcpp::ParameterValue(1.0));
83 weight_ =
static_cast<float>(node->get_parameter(
getName() +
".weight").as_double());
89 costmap_ = costmap_subscriber_->getCostmap();
98 const EdgeType & ,
float & cost)
101 RCLCPP_WARN_THROTTLE(logger_, *clock_, 1000,
"No costmap yet received!");
105 float largest_cost = 0.0, running_cost = 0.0, point_cost = 0.0;
106 unsigned int x0, y0, x1, y1, idx = 0;
107 if (!costmap_->worldToMap(edge->start->coords.x, edge->start->coords.y, x0, y0) ||
108 !costmap_->worldToMap(edge->end->coords.x, edge->end->coords.y, x1, y1))
110 if (invalid_off_map_) {
118 point_cost =
static_cast<float>(costmap_->getCost(iter.getX(), iter.getY()));
119 if (point_cost >= max_cost_ && max_cost_ != 255.0f && invalid_on_collision_) {
125 running_cost += point_cost;
126 if (largest_cost < point_cost && point_cost != 255.0) {
127 largest_cost = point_cost;
131 for (
unsigned int i = 0; i < check_resolution_; i++) {
137 cost = weight_ * largest_cost / max_cost_;
139 cost = weight_ * running_cost / (
static_cast<float>(idx) * max_cost_);
152 #include "pluginlib/class_list_macros.hpp"
Scores edges by the average or maximum cost found while iterating over the edge's line segment in the...
std::string getName() override
Get name of the plugin for parameter scope mapping.
void prepare() override
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests,...
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
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.
A plugin interface to score edges during graph search to modify the lowest cost path (e....
An iterator implementing Bresenham Ray-Tracing.
bool isValid() const
If the iterator is valid.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...