Commit 75f24c4 1 parent 7081a61 commit 75f24c4 Copy full SHA for 75f24c4
File tree 1 file changed +10
-1
lines changed
localization/ndt_scan_matcher/src
1 file changed +10
-1
lines changed Original file line number Diff line number Diff line change @@ -78,7 +78,16 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position)
78
78
79
79
ndt_ptr_->setParams (param);
80
80
81
- update_ndt (position, *ndt_ptr_);
81
+ const bool updated = update_ndt (position, *ndt_ptr_);
82
+ if (!updated) {
83
+ RCLCPP_ERROR_STREAM_THROTTLE (
84
+ logger_, *clock_, 1000 ,
85
+ " update_ndt failed. If this happens with initial position estimation, make sure that"
86
+ " (1) the initial position matches the pcd map and (2) the map_loader is working properly." );
87
+ last_update_position_ = position;
88
+ ndt_ptr_mutex_->unlock ();
89
+ return ;
90
+ }
82
91
ndt_ptr_->setInputSource (input_source);
83
92
ndt_ptr_mutex_->unlock ();
84
93
need_rebuild_ = false ;
You can’t perform that action at this time.
0 commit comments