41 #include "tf2/convert.hpp"
42 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
44 #include "nav2_costmap_2d/costmap_filters/keepout_filter.hpp"
45 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
51 : filter_info_sub_(nullptr), mask_sub_(nullptr), filter_mask_(nullptr),
57 const std::string & filter_info_topic)
59 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
61 nav2::LifecycleNode::SharedPtr node = node_.lock();
63 throw std::runtime_error{
"Failed to lock node"};
70 "KeepoutFilter: Subscribing to \"%s\" topic for filter info...",
72 filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
74 std::bind(&KeepoutFilter::filterInfoCallback,
this, std::placeholders::_1),
77 global_frame_ = layered_costmap_->getGlobalFrameID();
80 node->get_parameter(name_ +
"." +
"override_lethal_cost", override_lethal_cost_);
81 declareParameter(
"lethal_override_cost", rclcpp::ParameterValue(MAX_NON_OBSTACLE));
82 node->get_parameter(name_ +
"." +
"lethal_override_cost", lethal_override_cost_);
85 lethal_override_cost_ = \
86 std::clamp<unsigned int>(lethal_override_cost_, FREE_SPACE, MAX_NON_OBSTACLE);
89 void KeepoutFilter::filterInfoCallback(
90 const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
92 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
94 nav2::LifecycleNode::SharedPtr node = node_.lock();
96 throw std::runtime_error{
"Failed to lock node"};
106 "KeepoutFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
113 if (msg->base != BASE_DEFAULT || msg->multiplier != MULTIPLIER_DEFAULT) {
116 "KeepoutFilter: For proper use of keepout filter base and multiplier"
117 " in CostmapFilterInfo message should be set to their default values (%f and %f)",
118 BASE_DEFAULT, MULTIPLIER_DEFAULT);
126 "KeepoutFilter: Subscribing to \"%s\" topic for filter mask...",
128 mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
130 std::bind(&KeepoutFilter::maskCallback,
this, std::placeholders::_1),
134 void KeepoutFilter::maskCallback(
135 const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
137 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
139 nav2::LifecycleNode::SharedPtr node = node_.lock();
141 throw std::runtime_error{
"Failed to lock node"};
147 "KeepoutFilter: Received filter mask from %s topic.",
mask_topic_.c_str());
151 "KeepoutFilter: New filter mask arrived from %s topic. Updating old filter mask.",
153 filter_mask_.reset();
162 int min_i,
int min_j,
int max_i,
int max_j,
163 const geometry_msgs::msg::Pose & pose)
165 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
169 RCLCPP_WARN_THROTTLE(
170 logger_, *(clock_), 2000,
171 "KeepoutFilter: Filter mask was not received");
175 tf2::Transform tf2_transform;
176 tf2_transform.setIdentity();
177 int mg_min_x, mg_min_y;
178 int mg_max_x, mg_max_y;
180 const std::string mask_frame = filter_mask_->header.frame_id;
182 if (mask_frame != global_frame_) {
185 geometry_msgs::msg::TransformStamped transform;
187 transform = tf_->lookupTransform(
188 mask_frame, global_frame_, tf2::TimePointZero,
190 }
catch (tf2::TransformException & ex) {
193 "KeepoutFilter: Failed to get costmap frame (%s) "
194 "transformation to mask frame (%s) with error: %s",
195 global_frame_.c_str(), mask_frame.c_str(), ex.what());
198 tf2::fromMsg(transform.transform, tf2_transform);
229 const double half_cell_size = 0.5 * filter_mask_->info.resolution;
230 wx = filter_mask_->info.origin.position.x + half_cell_size;
231 wy = filter_mask_->info.origin.position.y + half_cell_size;
234 if (mg_min_x >= max_i || mg_min_y >= max_j) {
238 mg_min_x = std::max(min_i, mg_min_x);
239 mg_min_y = std::max(min_j, mg_min_y);
243 wx = filter_mask_->info.origin.position.x +
244 filter_mask_->info.width * filter_mask_->info.resolution + half_cell_size;
245 wy = filter_mask_->info.origin.position.y +
246 filter_mask_->info.height * filter_mask_->info.resolution + half_cell_size;
249 if (mg_max_x <= min_i || mg_max_y <= min_j) {
253 mg_max_x = std::min(max_i, mg_max_x);
254 mg_max_y = std::min(max_j, mg_max_y);
258 unsigned int mg_min_x_u =
static_cast<unsigned int>(mg_min_x);
259 unsigned int mg_min_y_u =
static_cast<unsigned int>(mg_min_y);
260 unsigned int mg_max_x_u =
static_cast<unsigned int>(mg_max_x);
261 unsigned int mg_max_y_u =
static_cast<unsigned int>(mg_max_y);
264 bool is_pose_lethal =
false;
265 if (override_lethal_cost_) {
266 geometry_msgs::msg::Pose mask_pose;
267 if (
transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
268 unsigned int mask_robot_i, mask_robot_j;
269 if (
worldToMask(filter_mask_, mask_pose.position.x, mask_pose.position.y, mask_robot_i,
272 auto data =
getMaskCost(filter_mask_, mask_robot_i, mask_robot_j);
273 is_pose_lethal = (data == INSCRIBED_INFLATED_OBSTACLE || data == LETHAL_OBSTACLE);
274 if (is_pose_lethal) {
275 RCLCPP_WARN_THROTTLE(
276 logger_, *(clock_), 2000,
277 "KeepoutFilter: Pose is in keepout zone, reducing cost override to navigate out.");
284 if (is_pose_lethal || (last_pose_lethal_ && !is_pose_lethal)) {
285 lethal_state_update_min_x_ = std::min(mg_min_x_u, lethal_state_update_min_x_);
286 mg_min_x_u = lethal_state_update_min_x_;
287 lethal_state_update_min_y_ = std::min(mg_min_y_u, lethal_state_update_min_y_);
288 mg_min_y_u = lethal_state_update_min_y_;
289 lethal_state_update_max_x_ = std::max(mg_max_x_u, lethal_state_update_max_x_);
290 mg_max_x_u = lethal_state_update_max_x_;
291 lethal_state_update_max_y_ = std::max(mg_max_y_u, lethal_state_update_max_y_);
292 mg_max_y_u = lethal_state_update_max_y_;
297 lethal_state_update_max_x_ = 0u;
298 lethal_state_update_max_y_ = 0u;
305 double msk_wx, msk_wy;
307 unsigned char data, old_data;
311 unsigned char * master_array = master_grid.
getCharMap();
312 for (i = mg_min_x_u; i < mg_max_x_u; i++) {
313 for (j = mg_min_y_u; j < mg_max_y_u; j++) {
315 old_data = master_array[index];
319 if (mask_frame != global_frame_) {
321 tf2::Vector3 point(gl_wx, gl_wy, 0);
322 point = tf2_transform * point;
331 if (
worldToMask(filter_mask_, msk_wx, msk_wy, mx, my)) {
334 if (data == NO_INFORMATION) {
338 if (data > old_data || old_data == NO_INFORMATION) {
339 if (override_lethal_cost_ && is_pose_lethal) {
340 master_array[index] = lethal_override_cost_;
342 master_array[index] = data;
349 last_pose_lethal_ = is_pose_lethal;
354 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
356 filter_info_sub_.reset();
362 std::lock_guard<CostmapFilter::mutex_t> guard(*
getMutex());
372 #include "pluginlib/class_list_macros.hpp"
A QoS profile for latched, reliable topics with a history of 10 messages.
A 2D costmap provides a mapping between points in the world and their associated "costs".
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
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
tf2::Duration transform_tolerance_
: mask_frame->global_frame_ transform tolerance
unsigned char getMaskCost(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int &my) const
Get the cost of a cell in the filter mask.
mutex_t * getMutex()
: returns pointer to a mutex
Reads in a keepout mask and marks keepout regions in the map to prevent planning or control in restri...
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.
KeepoutFilter()
A constructor.
void resetFilter()
Reset the costmap filter / topic / info.
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
bool isActive()
If this filter is active.
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.