Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix ObstacleLayer not working due to #2489 #3018

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,7 @@ class ObstacleLayer : public CostmapLayer
bool rolling_window_;
bool was_reset_;
int combination_method_;
bool active_{false};
};

} // namespace nav2_costmap_2d
Expand Down
21 changes: 8 additions & 13 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,6 @@ void ObstacleLayer::onInitialize()
if (data_type == "LaserScan") {
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
sub->unsubscribe();

auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*sub, *tf_, global_frame_, 50,
Expand Down Expand Up @@ -252,7 +251,6 @@ void ObstacleLayer::onInitialize()
} else {
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
sub->unsubscribe();

if (inf_is_valid) {
RCLCPP_WARN(
Expand Down Expand Up @@ -321,6 +319,8 @@ ObstacleLayer::laserScanCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr message,
const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
{
if (!active_) {return;}

// project the laser into a point cloud
sensor_msgs::msg::PointCloud2 cloud;
cloud.header = message->header;
Expand Down Expand Up @@ -355,6 +355,8 @@ ObstacleLayer::laserScanValidInfCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
{
if (!active_) {return;}

// Filter positive infinities ("Inf"s) to max_range.
float epsilon = 0.0001; // a tenth of a millimeter
sensor_msgs::msg::LaserScan message = *raw_message;
Expand Down Expand Up @@ -398,6 +400,8 @@ ObstacleLayer::pointCloud2Callback(
sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
const std::shared_ptr<ObservationBuffer> & buffer)
{
if (!active_) {return;}

// buffer the point cloud
buffer->lock();
buffer->bufferCloud(*message);
Expand Down Expand Up @@ -697,23 +701,14 @@ ObstacleLayer::activate()
notifier->clear();
}

// if we're stopped we need to re-subscribe to topics
for (unsigned int i = 0; i < observation_subscribers_.size(); ++i) {
if (observation_subscribers_[i] != NULL) {
observation_subscribers_[i]->subscribe();
}
}
resetBuffersLastUpdated();
active_ = true;
}

void
ObstacleLayer::deactivate()
{
for (unsigned int i = 0; i < observation_subscribers_.size(); ++i) {
if (observation_subscribers_[i] != NULL) {
observation_subscribers_[i]->unsubscribe();
}
}
active_ = false;
}

void
Expand Down