diff --git a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp index 5d634c2939132..2ec23ddba66f5 100644 --- a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp +++ b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp @@ -93,6 +93,7 @@ class ElevationMapLoaderNode : public rclcpp::Node grid_map::GridMap elevation_map_; std::string layer_name_; std::string map_frame_; + std::string elevation_map_directory_; bool use_inpaint_; float inpaint_radius_; bool use_elevation_map_cloud_publisher_; diff --git a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp index 5ec34174d9e93..5f7d855cac6c7 100644 --- a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp @@ -55,7 +55,7 @@ ElevationMapLoaderNode::ElevationMapLoaderNode(const rclcpp::NodeOptions & optio inpaint_radius_ = this->declare_parameter("inpaint_radius", 0.3); use_elevation_map_cloud_publisher_ = this->declare_parameter("use_elevation_map_cloud_publisher", false); - + elevation_map_directory_ = this->declare_parameter("elevation_map_directory", "path_default"); const bool use_lane_filter = this->declare_parameter("use_lane_filter", false); data_manager_.use_lane_filter_ = use_lane_filter; @@ -124,10 +124,8 @@ void ElevationMapLoaderNode::onMapHash( { RCLCPP_INFO(this->get_logger(), "subscribe map_hash"); const auto elevation_map_hash = map_hash->pcd; - const std::string elevation_map_directory = - this->declare_parameter("elevation_map_directory", "path_default"); data_manager_.elevation_map_path_ = std::make_unique( - std::filesystem::path(elevation_map_directory) / elevation_map_hash); + std::filesystem::path(elevation_map_directory_) / elevation_map_hash); if (data_manager_.isInitialized()) { publish(); }