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(elevation_map_loader): remove and create map bagfile if it cannot be loaded (backport #1772) #218

Merged
merged 1 commit into from
Dec 23, 2022
Merged
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 perception/elevation_map_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rosbag2_storage_default_plugins</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
Expand Down
22 changes: 20 additions & 2 deletions perception/elevation_map_loader/src/elevation_map_loader_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#define EIGEN_MPL2_ONLY
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp>

ElevationMapLoaderNode::ElevationMapLoaderNode(const rclcpp::NodeOptions & options)
: Node("elevation_map_loader", options)
Expand Down Expand Up @@ -102,8 +103,25 @@ void ElevationMapLoaderNode::publish()
RCLCPP_INFO(
this->get_logger(), "Load elevation map from: %s",
data_manager_.elevation_map_path_->c_str());
grid_map::GridMapRosConverter::loadFromBag(
*data_manager_.elevation_map_path_, "elevation_map", elevation_map_);

// Check if bag can be loaded
bool is_bag_loaded = false;
try {
is_bag_loaded = grid_map::GridMapRosConverter::loadFromBag(
*data_manager_.elevation_map_path_, "elevation_map", elevation_map_);
} catch (rosbag2_storage_plugins::SqliteException & e) {
is_bag_loaded = false;
}
if (!is_bag_loaded) {
// Delete directory including elevation map if bag is broken
RCLCPP_ERROR(
this->get_logger(), "Try to loading bag, but bag is broken. Remove %s",
data_manager_.elevation_map_path_->c_str());
std::filesystem::remove_all(data_manager_.elevation_map_path_->c_str());
// Create elevation map from pointcloud map if bag is broken
RCLCPP_INFO(this->get_logger(), "Create elevation map from pointcloud map ");
createElevationMap();
}
}

elevation_map_.setFrameId(map_frame_);
Expand Down