APM: updates for MAVLink 1.0

This commit is contained in:
Andrew Tridgell 2012-04-24 19:52:48 +10:00
parent 373577136e
commit 95be2c5922
1 changed files with 6 additions and 13 deletions

View File

@ -142,7 +142,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_present |= (1<<2); // compass present control_sensors_present |= (1<<2); // compass present
} }
control_sensors_present |= (1<<3); // absolute pressure sensor present control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps != NULL && g_gps->fix) { if (g_gps != NULL && g_gps->status() == GPS::GPS_OK) {
control_sensors_present |= (1<<5); // GPS present control_sensors_present |= (1<<5); // GPS present
} }
control_sensors_present |= (1<<10); // 3D angular rate control control_sensors_present |= (1<<10); // 3D angular rate control
@ -338,11 +338,9 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
static void NOINLINE send_gps_raw(mavlink_channel_t chan) static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{ {
#ifdef MAVLINK10 #ifdef MAVLINK10
uint8_t fix; uint8_t fix = g_gps->status();
if (g_gps->status() == 2) { if (fix == GPS::GPS_OK) {
fix = 3; fix = 3;
} else {
fix = 0;
} }
mavlink_msg_gps_raw_int_send( mavlink_msg_gps_raw_int_send(
@ -1109,15 +1107,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
break; break;
#if 0 case MAV_CMD_MISSION_START:
// not implemented yet, but could implement some of them set_mode(AUTO);
case MAV_CMD_NAV_LAND: result = MAV_RESULT_ACCEPTED;
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_NAV_ROI:
case MAV_CMD_NAV_PATHPLANNING:
break; break;
#endif
case MAV_CMD_PREFLIGHT_CALIBRATION: case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 || if (packet.param1 == 1 ||