Skip to content

Commit

Permalink
sys_status.cpp: improve timeout code
Browse files Browse the repository at this point in the history
# Conflicts:
#	mavros/src/plugins/sys_status.cpp
  • Loading branch information
amilcarlucas authored and vooon committed Feb 29, 2024
1 parent b35b9f1 commit 533d64d
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -395,11 +395,12 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
ros::Time last_rcd_;
last_rcd_.fromNSec(last_rcd.load());
constexpr int timeout = 10.0; // seconds
const ros::Duration timeout_duration = ros::Duration(timeout);

// summarize the results
if (last_rcd_.isZero()) {
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
} else if (ros::Time::now().toSec() - last_rcd_.toSec() > timeout) {
} else if (ros::Time::now() - last_rcd_ > timeout_duration) {
stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
} else {
if (freemem == UINT32_MAX)
Expand Down Expand Up @@ -445,9 +446,10 @@ class HwStatus : public diagnostic_updater::DiagnosticTask
{
std::lock_guard<std::mutex> lock(mutex);
constexpr int timeout = 10.0; // seconds
const ros::Duration timeout_duration = ros::Duration(timeout);
if (last_rcd.isZero()) {
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
} else if (ros::Time::now().toSec() - last_rcd.toSec() > timeout) {
} else if (ros::Time::now() - last_rcd > timeout_duration) {
stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
} else {
if (vcc < 0)
Expand Down

0 comments on commit 533d64d

Please sign in to comment.