Skip to content

Commit

Permalink
sys_status.cpp: When current data not available, obey the ROS standard
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Feb 16, 2022
1 parent bbf379b commit cd6693e
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -396,7 +396,7 @@ class HwStatus : public diagnostic_updater::DiagnosticTask

void set(uint16_t v, uint8_t e) {
std::lock_guard<std::mutex> lock(mutex);
vcc = v / 1000.0;
vcc = v * 0.001f;
i2cerr = e;
}

Expand Down Expand Up @@ -870,7 +870,7 @@ class SystemStatusPlugin : public plugin::PluginBase
auto batt_msg = boost::make_shared<BatteryMsg>();
batt_msg->header.stamp = ros::Time::now();

batt_msg->current = -(bs.current_battery * 0.01f); // 10 mA
batt_msg->current = bs.current_battery==-1?NAN:-(bs.current_battery * 0.01f); // 10 mA
batt_msg->charge = NAN;
batt_msg->capacity = NAN;
batt_msg->design_capacity = NAN;
Expand Down

0 comments on commit cd6693e

Please sign in to comment.