38 #include "nav2_costmap_2d/costmap_filters/binary_filter.hpp"
45 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
46 #include "nav2_util/occ_grid_values.hpp"
52 : filter_info_sub_(nullptr), mask_sub_(nullptr),
53 binary_state_pub_(nullptr), filter_mask_(nullptr), mask_frame_(
""), global_frame_(
""),
54 default_state_(false), binary_state_(default_state_)
59 const std::string & filter_info_topic)
61 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
63 rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
65 throw std::runtime_error{
"Failed to lock node"};
69 std::string binary_state_topic;
71 node->get_parameter(name_ +
"." +
"default_state", default_state_);
72 declareParameter(
"binary_state_topic", rclcpp::ParameterValue(
"binary_state"));
73 node->get_parameter(name_ +
"." +
"binary_state_topic", binary_state_topic);
75 node->get_parameter(name_ +
"." +
"flip_threshold", flip_threshold_);
81 "BinaryFilter: Subscribing to \"%s\" topic for filter info...",
83 filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
85 std::bind(&BinaryFilter::filterInfoCallback,
this, std::placeholders::_1));
88 global_frame_ = layered_costmap_->getGlobalFrameID();
91 binary_state_pub_ = node->create_publisher<std_msgs::msg::Bool>(
92 binary_state_topic, rclcpp::QoS(10));
93 binary_state_pub_->on_activate();
97 multiplier_ = MULTIPLIER_DEFAULT;
100 changeState(default_state_);
103 void BinaryFilter::filterInfoCallback(
104 const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
106 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
108 rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
110 throw std::runtime_error{
"Failed to lock node"};
120 "BinaryFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
126 if (msg->type != BINARY_FILTER) {
127 RCLCPP_ERROR(logger_,
"BinaryFilter: Mode %i is not supported", msg->type);
133 multiplier_ = msg->multiplier;
140 "BinaryFilter: Subscribing to \"%s\" topic for filter mask...",
142 mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
143 mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
144 std::bind(&BinaryFilter::maskCallback,
this, std::placeholders::_1));
147 void BinaryFilter::maskCallback(
148 const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
150 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
155 "BinaryFilter: Received filter mask from %s topic.",
mask_topic_.c_str());
159 "BinaryFilter: New filter mask arrived from %s topic. Updating old filter mask.",
161 filter_mask_.reset();
165 mask_frame_ = msg->header.frame_id;
170 int ,
int ,
int ,
int ,
171 const geometry_msgs::msg::Pose2D & pose)
173 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
177 RCLCPP_WARN_THROTTLE(
178 logger_, *(clock_), 2000,
179 "BinaryFilter: Filter mask was not received");
183 geometry_msgs::msg::Pose2D mask_pose;
186 if (!
transformPose(global_frame_, pose, mask_frame_, mask_pose)) {
191 unsigned int mask_robot_i, mask_robot_j;
192 if (!
worldToMask(filter_mask_, mask_pose.x, mask_pose.y, mask_robot_i, mask_robot_j)) {
196 "BinaryFilter: Robot is outside of filter mask. Resetting binary state to default.");
197 changeState(default_state_);
202 int8_t mask_data =
getMaskData(filter_mask_, mask_robot_i, mask_robot_j);
203 if (mask_data == nav2_util::OCC_GRID_UNKNOWN) {
206 RCLCPP_WARN_THROTTLE(
207 logger_, *(clock_), 2000,
208 "BinaryFilter: Filter mask [%i, %i] data is unknown. Do nothing.",
209 mask_robot_i, mask_robot_j);
213 if (base_ + mask_data * multiplier_ > flip_threshold_) {
214 if (binary_state_ == default_state_) {
215 changeState(!default_state_);
218 if (binary_state_ != default_state_) {
219 changeState(default_state_);
226 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
228 RCLCPP_INFO(logger_,
"BinaryFilter: Resetting the filter to default state");
229 changeState(default_state_);
231 filter_info_sub_.reset();
233 if (binary_state_pub_) {
234 binary_state_pub_->on_deactivate();
235 binary_state_pub_.reset();
241 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
249 void BinaryFilter::changeState(
const bool state)
251 binary_state_ = state;
253 RCLCPP_INFO(logger_,
"BinaryFilter: Switched on");
255 RCLCPP_INFO(logger_,
"BinaryFilter: Switched off");
259 std::unique_ptr<std_msgs::msg::Bool> msg =
260 std::make_unique<std_msgs::msg::Bool>();
262 binary_state_pub_->publish(std::move(msg));
267 #include "pluginlib/class_list_macros.hpp"
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.
BinaryFilter()
A constructor.
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.
bool isActive()
If this filter is active.
void resetFilter()
Reset the costmap filter / topic / info.
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.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.