mirror of https://github.com/ArduPilot/ardupilot
Sub: accept MISSION_START as both long and int
This commit is contained in:
parent
8999790ff0
commit
c1e12f691e
|
@ -468,6 +468,9 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_
|
|||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
|
||||
|
||||
case MAV_CMD_MISSION_START:
|
||||
return handle_MAV_CMD_MISSION_START(packet);
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
return handle_MAV_CMD_NAV_LOITER_UNLIM(packet);
|
||||
|
||||
|
@ -523,15 +526,17 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon
|
|||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
||||
case MAV_CMD_MISSION_START:
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (sub.motors.armed() && sub.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
|
||||
|
|
|
@ -53,6 +53,7 @@ private:
|
|||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
||||
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet);
|
||||
|
|
Loading…
Reference in New Issue