mirror of https://github.com/ArduPilot/ardupilot
add method of detecting if motors are armed
This commit is contained in:
parent
2c73d89400
commit
e20d3a3676
|
@ -73,6 +73,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||
}
|
||||
|
||||
uint8_t status = MAV_STATE_ACTIVE;
|
||||
|
||||
if (!motor_armed) {
|
||||
status = MAV_STATE_STANDBY;
|
||||
}
|
||||
|
||||
uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000
|
||||
|
||||
mavlink_msg_sys_status_send(
|
||||
|
|
Loading…
Reference in New Issue