Skip to content

Commit

Permalink
the actual execution time added to diagnostics message
Browse files Browse the repository at this point in the history
  • Loading branch information
yvzksgl committed Sep 11, 2023
1 parent 5344d61 commit eeef736
Showing 1 changed file with 1 addition and 4 deletions.
5 changes: 1 addition & 4 deletions localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@ NDTScanMatcher::NDTScanMatcher()
converged_param_type_(ConvergedParamType::TRANSFORM_PROBABILITY),
converged_param_transform_probability_(4.5),
converged_param_nearest_voxel_transformation_likelihood_(2.3),
critical_upperbound_exe_time_(24),
initial_estimate_particles_num_(100),
initial_pose_timeout_sec_(1.0),
initial_pose_distance_tolerance_m_(10.0),
Expand Down Expand Up @@ -146,8 +145,6 @@ NDTScanMatcher::NDTScanMatcher()
critical_upper_bound_exe_time_ms_ =
this->declare_parameter("critical_upper_bound_exe_time_ms", critical_upper_bound_exe_time_ms_);

Check warning on line 147 in localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

NDTScanMatcher::NDTScanMatcher increases from 146 to 149 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
critical_upperbound_exe_time_ = this->declare_parameter("critical_upperbound_exe_time",critical_upperbound_exe_time_);

initial_pose_timeout_sec_ =
this->declare_parameter("initial_pose_timeout_sec", initial_pose_timeout_sec_);

Expand Down Expand Up @@ -292,7 +289,7 @@ void NDTScanMatcher::timer_diagnostic()
state_ptr_->count("execution_time") &&
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. ";
diag_status_msg.message += "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])";
}

Check warning on line 293 in localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

NDTScanMatcher::timer_diagnostic increases in cyclomatic complexity from 12 to 14, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
// Ignore local optimal solution
if (
Expand Down

0 comments on commit eeef736

Please sign in to comment.