38 #include "nav2_costmap_2d/costmap_filters/speed_filter.hpp"
45 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
51 : filter_info_sub_(nullptr), mask_sub_(nullptr),
52 speed_limit_pub_(nullptr), filter_mask_(nullptr), global_frame_(
""),
53 speed_limit_(NO_SPEED_LIMIT), speed_limit_prev_(NO_SPEED_LIMIT)
58 const std::string & filter_info_topic)
60 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
62 rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
64 throw std::runtime_error{
"Failed to lock node"};
68 std::string speed_limit_topic;
69 declareParameter(
"speed_limit_topic", rclcpp::ParameterValue(
"speed_limit"));
70 node->get_parameter(name_ +
"." +
"speed_limit_topic", speed_limit_topic);
77 "SpeedFilter: Subscribing to \"%s\" topic for filter info...",
79 filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
81 std::bind(&SpeedFilter::filterInfoCallback,
this, std::placeholders::_1));
84 global_frame_ = layered_costmap_->getGlobalFrameID();
87 speed_limit_pub_ = node->create_publisher<nav2_msgs::msg::SpeedLimit>(
88 speed_limit_topic, rclcpp::QoS(10));
89 speed_limit_pub_->on_activate();
93 multiplier_ = MULTIPLIER_DEFAULT;
97 void SpeedFilter::filterInfoCallback(
98 const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
100 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
102 rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
104 throw std::runtime_error{
"Failed to lock node"};
114 "SpeedFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
122 multiplier_ = msg->multiplier;
123 if (msg->type == SPEED_FILTER_PERCENT) {
128 "SpeedFilter: Using expressed in a percent from maximum speed"
129 "speed_limit = %f + filter_mask_data * %f",
131 }
else if (msg->type == SPEED_FILTER_ABSOLUTE) {
136 "SpeedFilter: Using absolute speed_limit = %f + filter_mask_data * %f",
139 RCLCPP_ERROR(logger_,
"SpeedFilter: Mode is not supported");
148 "SpeedFilter: Subscribing to \"%s\" topic for filter mask...",
150 mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
151 mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
152 std::bind(&SpeedFilter::maskCallback,
this, std::placeholders::_1));
155 void SpeedFilter::maskCallback(
156 const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
158 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
163 "SpeedFilter: Received filter mask from %s topic.",
mask_topic_.c_str());
167 "SpeedFilter: New filter mask arrived from %s topic. Updating old filter mask.",
169 filter_mask_.reset();
177 int ,
int ,
int ,
int ,
178 const geometry_msgs::msg::Pose2D & pose)
180 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
184 RCLCPP_WARN_THROTTLE(
185 logger_, *(clock_), 2000,
186 "SpeedFilter: Filter mask was not received");
190 geometry_msgs::msg::Pose2D mask_pose;
193 if (!
transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
198 unsigned int mask_robot_i, mask_robot_j;
199 if (!
worldToMask(filter_mask_, mask_pose.x, mask_pose.y, mask_robot_i, mask_robot_j)) {
205 int8_t speed_mask_data =
getMaskData(filter_mask_, mask_robot_i, mask_robot_j);
206 if (speed_mask_data == SPEED_MASK_NO_LIMIT) {
209 speed_limit_ = NO_SPEED_LIMIT;
210 }
else if (speed_mask_data == SPEED_MASK_UNKNOWN) {
215 "SpeedFilter: Found unknown cell in filter_mask[%i, %i], "
216 "which is invalid for this kind of filter",
217 mask_robot_i, mask_robot_j);
221 speed_limit_ = speed_mask_data * multiplier_ + base_;
223 if (speed_limit_ < 0.0 || speed_limit_ > 100.0) {
226 "SpeedFilter: Speed limit in filter_mask[%i, %i] is %f%%, "
227 "out of bounds of [0, 100]. Setting it to no-limit value.",
228 mask_robot_i, mask_robot_j, speed_limit_);
229 speed_limit_ = NO_SPEED_LIMIT;
232 if (speed_limit_ < 0.0) {
235 "SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0 m/s, "
236 "which can not be true. Setting it to no-limit value.",
237 mask_robot_i, mask_robot_j);
238 speed_limit_ = NO_SPEED_LIMIT;
243 if (speed_limit_ != speed_limit_prev_) {
244 if (speed_limit_ != NO_SPEED_LIMIT) {
245 RCLCPP_DEBUG(logger_,
"SpeedFilter: Speed limit is set to %f", speed_limit_);
247 RCLCPP_DEBUG(logger_,
"SpeedFilter: Speed limit is set to its default value");
251 std::unique_ptr<nav2_msgs::msg::SpeedLimit> msg =
252 std::make_unique<nav2_msgs::msg::SpeedLimit>();
253 msg->header.frame_id = global_frame_;
254 msg->header.stamp = clock_->now();
255 msg->percentage = percentage_;
256 msg->speed_limit = speed_limit_;
257 speed_limit_pub_->publish(std::move(msg));
259 speed_limit_prev_ = speed_limit_;
265 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
267 filter_info_sub_.reset();
269 if (speed_limit_pub_) {
270 speed_limit_pub_->on_deactivate();
271 speed_limit_pub_.reset();
277 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
287 #include "pluginlib/class_list_macros.hpp"
A 2D costmap provides a mapping between points in the world and their associated "costs".
int8_t getMaskData(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int my) const
Get the data of a cell in the filter mask.
bool worldToMask(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, double wx, double wy, unsigned int &mx, unsigned int &my) const
: Convert from world coordinates to mask coordinates. Similar to Costmap2D::worldToMap() method but w...
bool transformPose(const std::string global_frame, const geometry_msgs::msg::Pose2D &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose2D &mask_pose) const
: Transforms robot pose from current layer frame to mask frame
std::string filter_info_topic_
: Name of costmap filter info topic
std::string mask_topic_
: Name of filter mask topic
mutex_t * getMutex()
: returns pointer to a mutex
Abstract class for layered costmap plugin implementations.
std::string joinWithParentNamespace(const std::string &topic)
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
void resetFilter()
Reset the costmap filter / topic / info.
void process(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose2D &pose)
Process the keepout layer at the current pose / bounds / grid.
SpeedFilter()
A constructor.
bool isActive()
If this filter is active.