Skip to content

Commit

Permalink
Send FS state to gcs for AC
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Feb 9, 2013
1 parent 88840eb commit 61e5b09
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion ArduCopter/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,11 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode;


if (ap.failsafe == true) {
system_status = MAV_STATE_CRITICAL;
}

// work out the base_mode. This value is not very useful
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
Expand Down

0 comments on commit 61e5b09

Please sign in to comment.