File tree Expand file tree Collapse file tree 1 file changed +10
-6
lines changed Expand file tree Collapse file tree 1 file changed +10
-6
lines changed Original file line number Diff line number Diff line change @@ -1857,16 +1857,20 @@ void RosFilter<T>::loadParams()
18571857 RCLCPP_FATAL_STREAM (get_logger (), error);
18581858 throw std::invalid_argument (error);
18591859 }
1860+ return true ;
18601861 }
1862+ return false ;
18611863 };
18621864
1863- load_covariance (" process_noise_covariance" , process_noise_covariance_);
1864- RF_DEBUG (" Process noise covariance is:\n " << process_noise_covariance_ << " \n " );
1865- filter_.setProcessNoiseCovariance (process_noise_covariance_);
1865+ if (load_covariance (" process_noise_covariance" , process_noise_covariance_)) {
1866+ RF_DEBUG (" Process noise covariance is:\n " << process_noise_covariance_ << " \n " );
1867+ filter_.setProcessNoiseCovariance (process_noise_covariance_);
1868+ }
18661869
1867- load_covariance (" initial_estimate_covariance" , initial_estimate_error_covariance_);
1868- RF_DEBUG (" Initial estimate covariance is:\n " << initial_estimate_error_covariance_ << " \n " );
1869- filter_.setEstimateErrorCovariance (initial_estimate_error_covariance_);
1870+ if (load_covariance (" initial_estimate_covariance" , initial_estimate_error_covariance_)) {
1871+ RF_DEBUG (" Initial estimate covariance is:\n " << initial_estimate_error_covariance_ << " \n " );
1872+ filter_.setEstimateErrorCovariance (initial_estimate_error_covariance_);
1873+ }
18701874}
18711875
18721876template <typename T>
You can’t perform that action at this time.
0 commit comments