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), 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 nav2::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),
89 global_frame_ = layered_costmap_->getGlobalFrameID();
92 binary_state_pub_ = node->create_publisher<std_msgs::msg::Bool>(
94 binary_state_pub_->on_activate();
98 multiplier_ = MULTIPLIER_DEFAULT;
101 changeState(binary_state_);
104 void BinaryFilter::filterInfoCallback(
105 const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
107 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
109 nav2::LifecycleNode::SharedPtr node = node_.lock();
111 throw std::runtime_error{
"Failed to lock node"};
121 "BinaryFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
127 if (msg->type != BINARY_FILTER) {
128 RCLCPP_ERROR(logger_,
"BinaryFilter: Mode %i is not supported", msg->type);
134 multiplier_ = msg->multiplier;
141 "BinaryFilter: Subscribing to \"%s\" topic for filter mask...",
143 mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
145 std::bind(&BinaryFilter::maskCallback,
this, std::placeholders::_1),
149 void BinaryFilter::maskCallback(
150 const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
152 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
157 "BinaryFilter: Received filter mask from %s topic.",
mask_topic_.c_str());
161 "BinaryFilter: New filter mask arrived from %s topic. Updating old filter mask.",
163 filter_mask_.reset();
171 int ,
int ,
int ,
int ,
172 const geometry_msgs::msg::Pose & pose)
174 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
178 RCLCPP_WARN_THROTTLE(
179 logger_, *(clock_), 2000,
180 "BinaryFilter: Filter mask was not received");
184 geometry_msgs::msg::Pose mask_pose;
187 if (!
transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
192 unsigned int mask_robot_i, mask_robot_j;
193 if (!
worldToMask(filter_mask_, mask_pose.position.x, mask_pose.position.y, mask_robot_i,
199 "BinaryFilter: Robot is outside of filter mask. Resetting binary state to default.");
200 changeState(default_state_);
205 int8_t mask_data =
getMaskData(filter_mask_, mask_robot_i, mask_robot_j);
206 if (mask_data == nav2_util::OCC_GRID_UNKNOWN) {
209 RCLCPP_WARN_THROTTLE(
210 logger_, *(clock_), 2000,
211 "BinaryFilter: Filter mask [%i, %i] data is unknown. Do nothing.",
212 mask_robot_i, mask_robot_j);
217 if (base_ + mask_data * multiplier_ > flip_threshold_) {
218 if (binary_state_ == default_state_) {
219 changeState(!default_state_);
222 if (binary_state_ != default_state_) {
223 changeState(default_state_);
230 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
233 std::unique_ptr<std_msgs::msg::Bool> msg =
234 std::make_unique<std_msgs::msg::Bool>();
235 msg->data = binary_state_;
236 binary_state_pub_->publish(std::move(msg));
238 filter_info_sub_.reset();
240 if (binary_state_pub_) {
241 binary_state_pub_->on_deactivate();
242 binary_state_pub_.reset();
248 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
256 void BinaryFilter::changeState(
const bool state)
258 binary_state_ = state;
260 RCLCPP_INFO(logger_,
"BinaryFilter: Switched on");
262 RCLCPP_INFO(logger_,
"BinaryFilter: Switched off");
266 std::unique_ptr<std_msgs::msg::Bool> msg =
267 std::make_unique<std_msgs::msg::Bool>();
269 binary_state_pub_->publish(std::move(msg));
274 #include "pluginlib/class_list_macros.hpp"
A QoS profile for latched, reliable topics with a history of 10 messages.
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
void process(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose &pose)
Process the keepout layer at the current pose / bounds / grid.
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
BinaryFilter()
A constructor.
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::Pose &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose &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.