Skip to content

Commit a1055b9

Browse files
authored
Fix bug in creating frequency diag. (#594)
1 parent 285a386 commit a1055b9

File tree

2 files changed

+14
-4
lines changed

2 files changed

+14
-4
lines changed

include/robot_localization/ros_filter.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -774,6 +774,16 @@ class RosFilter : public rclcpp::Node
774774
//! @brief optional signaling diagnostic frequency
775775
//!
776776
std::unique_ptr<diagnostic_updater::HeaderlessTopicDiagnostic> freq_diag_;
777+
778+
//! @brief minimum frequency threshold for frequency diagnostic
779+
//! Must be on heap since pointer is passed to diagnostic_updater::FrequencyStatusParam
780+
//!
781+
double min_frequency_;
782+
783+
//! @brief maximum frequency threshold for frequency diagnostic
784+
//! Must be on heap since pointer is passed to diagnostic_updater::FrequencyStatusParam
785+
//!
786+
double max_frequency_;
777787
};
778788

779789
} // namespace robot_localization

src/ros_filter.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1953,15 +1953,15 @@ void RosFilter<T>::initialize()
19531953
}
19541954

19551955
// Set up the frequency diagnostic
1956-
double minFrequency = frequency_ - 2;
1957-
double maxFrequency = frequency_ + 2;
1956+
min_frequency_ = frequency_ - 2;
1957+
max_frequency_ = frequency_ + 2;
19581958
freq_diag_ =
19591959
std::make_unique<diagnostic_updater::HeaderlessTopicDiagnostic>(
19601960
"odometry/filtered",
19611961
*diagnostic_updater_,
19621962
diagnostic_updater::FrequencyStatusParam(
1963-
&minFrequency,
1964-
&maxFrequency, 0.1, 10));
1963+
&min_frequency_,
1964+
&max_frequency_, 0.1, 10));
19651965

19661966
last_diag_time_ = this->now();
19671967

0 commit comments

Comments
 (0)