mirror of https://github.com/ArduPilot/ardupilot
COPTER: Add mavlink landing gear control
Add MAV_CMD_AIRFRAME_CONFIGURATION (# 2520), which is for landing gear control. Param 1 is not used in ArduPilot Param 2 is deploy/retract. 0 is deploy, 1 is Retract
This commit is contained in:
parent
a262099d35
commit
fd332287b2
|
@ -928,6 +928,21 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||
return MAV_RESULT_FAILED;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_AIRFRAME_CONFIGURATION: {
|
||||
// Param 1: Select which gear, not used in ArduPilot
|
||||
// Param 2: 0 = Deploy, 1 = Retract
|
||||
// For safety, anything other than 1 will deploy
|
||||
switch ((uint8_t)packet.param2) {
|
||||
case 1:
|
||||
copter.landinggear.set_position(AP_LandingGear::LandingGear_Retract);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
default:
|
||||
copter.landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
/* Solo user presses Fly button */
|
||||
case MAV_CMD_SOLO_BTN_FLY_CLICK: {
|
||||
if (copter.failsafe.radio) {
|
||||
|
|
Loading…
Reference in New Issue