Tracker: use handle_set_mode()

This commit is contained in:
Randy Mackay 2014-09-29 18:47:29 +09:00
parent 9453154b75
commit dbc1c03d49
2 changed files with 17 additions and 24 deletions

View File

@ -854,30 +854,7 @@ mission_failed:
case MAVLINK_MSG_ID_SET_MODE: case MAVLINK_MSG_ID_SET_MODE:
{ {
// decode handle_set_mode(msg, mavlink_set_mode);
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Also proxy it to the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
// custom_mode instead.
break;
}
switch (packet.custom_mode) {
case MANUAL:
case STOP:
case SCAN:
case AUTO:
set_mode((enum ControlMode)packet.custom_mode);
break;
}
break; break;
} }

View File

@ -212,6 +212,22 @@ static void set_mode(enum ControlMode mode)
} }
} }
/*
set_mode() wrapper for MAVLink SET_MODE
*/
static bool mavlink_set_mode(uint8_t mode)
{
switch (mode) {
case AUTO:
case MANUAL:
case SCAN:
case STOP:
set_mode((enum ControlMode)mode);
return true;
}
return false;
}
static void check_usb_mux(void) static void check_usb_mux(void)
{ {
bool usb_check = hal.gpio->usb_connected(); bool usb_check = hal.gpio->usb_connected();