GCS_MAVLink: added send_battery2()

This commit is contained in:
Andrew Tridgell 2014-08-09 12:14:06 +10:00
parent ab6302540d
commit 9a1bac06d4
2 changed files with 12 additions and 0 deletions

View File

@ -12,6 +12,7 @@
#include <GCS_MAVLink.h>
#include <DataFlash.h>
#include <AP_Mission.h>
#include <AP_BattMonitor.h>
#include <stdint.h>
// GCS Message ID's
@ -47,6 +48,7 @@ enum ap_message {
MSG_WIND,
MSG_RANGEFINDER,
MSG_TERRAIN,
MSG_BATTERY2,
MSG_RETRY_DEFERRED // this must be last
};
@ -195,6 +197,7 @@ public:
void send_scaled_pressure(AP_Baro &barometer);
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer);
void send_ahrs(AP_AHRS &ahrs);
void send_battery2(const AP_BattMonitor &battery);
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels

View File

@ -1153,3 +1153,12 @@ void GCS_MAVLINK::send_statustext_all(const prog_char_t *msg)
}
}
}
// report battery2 state
void GCS_MAVLINK::send_battery2(const AP_BattMonitor &battery)
{
float voltage;
if (battery.voltage2(voltage)) {
mavlink_msg_battery2_send(chan, voltage*1000, -1);
}
}