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

MEMINFO fixes #1732

Merged
merged 1 commit into from
Apr 14, 2022
Merged
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
12 changes: 6 additions & 6 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,12 +375,12 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
public:
MemInfo(const std::string &name) :
diagnostic_updater::DiagnosticTask(name),
freemem(-1),
freemem(UINT32_MAX),
brkval(0),
last_rcd(0)
{ }

void set(uint16_t f, uint16_t b) {
void set(uint32_t f, uint16_t b) {
freemem = f;
brkval = b;
last_rcd = ros::Time::now().toNSec();
Expand All @@ -389,7 +389,7 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
{
// access atomic variables just once
ssize_t freemem_ = freemem;
size_t freemem_ = freemem;
uint16_t brkval_ = brkval;
ros::Time last_rcd_;
last_rcd_.fromNSec(last_rcd.load());
Expand All @@ -401,7 +401,7 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
} else if (ros::Time::now().toSec() - last_rcd_.toSec() > timeout) {
stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
} else {
if (freemem < 0)
if (freemem == UINT32_MAX)
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data");
else if (freemem < 200)
stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Low mem");
Expand All @@ -413,7 +413,7 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
}

private:
std::atomic<ssize_t> freemem;
std::atomic<size_t> freemem;
std::atomic<uint16_t> brkval;
std::atomic<uint64_t> last_rcd;
};
Expand Down Expand Up @@ -876,7 +876,7 @@ class SystemStatusPlugin : public plugin::PluginBase

void handle_meminfo(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
{
mem_diag.set(mem.freemem, mem.brkval);
mem_diag.set(std::max(static_cast<uint32_t>(mem.freemem), mem.freemem32), mem.brkval);
}

void handle_hwstatus(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
Expand Down