diff --git a/localization/localization_node/src/localization_nodelet.cc b/localization/localization_node/src/localization_nodelet.cc index 72a4444d38..5363bafadb 100644 --- a/localization/localization_node/src/localization_nodelet.cc +++ b/localization/localization_node/src/localization_nodelet.cc @@ -74,6 +74,7 @@ bool LocalizationNodelet::ResetMap(const std::string& map_file) { map_.reset(); map_ = std::make_shared(last_valid_map_file_, true); inst_.reset(new Localizer(map_.get())); + ReadParams(); enabled_ = true; } else { ROS_ERROR_STREAM("No last valid map, please reset with a valid map. Not localizing.");