Skip to content
Merged
Changes from 1 commit
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
12 changes: 12 additions & 0 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,12 @@ ObstacleLayer::laserScanCallback(
global_frame_.c_str(),
ex.what());
projector_.projectLaser(*message, cloud);
} catch (std::runtime_error &ex) {
RCLCPP_WARN(
logger_,
"transformLaserScanToPointCloud error, it seems the message from laser is malformed. Ignore this message. what(): %s",
ex.what());
return; //ignore this message
}

// buffer the point cloud
Expand Down Expand Up @@ -327,6 +333,12 @@ ObstacleLayer::laserScanValidInfCallback(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
global_frame_.c_str(), ex.what());
projector_.projectLaser(message, cloud);
} catch (std::runtime_error &ex) {
RCLCPP_WARN(
logger_,
"transformLaserScanToPointCloud error, it seems the message from laser is malformed. Ignore this message. what(): %s",
ex.what());
return; //ignore this message
}

// buffer the point cloud
Expand Down