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(ndt_scan_matcher): fix type of critical_upper_bound_exe_time_ms #6161

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
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,9 @@
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
initial_pose_distance_tolerance_m: 10.0

# The execution time which means probably NDT cannot matches scans properly. [ms]
critical_upper_bound_exe_time_ms: 100.0

# Number of threads used for parallel computing
num_threads: 4

Expand Down Expand Up @@ -98,6 +101,3 @@

# If lidar_point.z - base_link.z <= this threshold , the point will be removed
z_margin_for_ground_removal: 0.8

# The execution time which means probably NDT cannot matches scans properly. [ms]
critical_upper_bound_exe_time_ms: 100
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ class NDTScanMatcher : public rclcpp::Node
double z_margin_for_ground_removal_;

// The execution time which means probably NDT cannot matches scans properly
int64_t critical_upper_bound_exe_time_ms_;
double critical_upper_bound_exe_time_ms_;
};

#endif // NDT_SCAN_MATCHER__NDT_SCAN_MATCHER_CORE_HPP_
5 changes: 2 additions & 3 deletions localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ NDTScanMatcher::NDTScanMatcher()
lidar_topic_timeout_sec_ = this->declare_parameter<double>("lidar_topic_timeout_sec");

critical_upper_bound_exe_time_ms_ =
this->declare_parameter<int64_t>("critical_upper_bound_exe_time_ms");
this->declare_parameter<double>("critical_upper_bound_exe_time_ms");

initial_pose_timeout_sec_ = this->declare_parameter<double>("initial_pose_timeout_sec");

Expand Down Expand Up @@ -316,8 +316,7 @@ void NDTScanMatcher::publish_diagnostic()
}
if (
state_ptr_->count("execution_time") &&
std::stod((*state_ptr_)["execution_time"]) >=
static_cast<double>(critical_upper_bound_exe_time_ms_)) {
std::stod((*state_ptr_)["execution_time"]) >= critical_upper_bound_exe_time_ms_) {
diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
diag_status_msg.message +=
"NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])";
Expand Down
Loading