mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: moved MAV_CMD_AIRFRAME_CONFIGURATION from copter
This commit is contained in:
parent
ab07a2ecf3
commit
fc904011fb
@ -655,6 +655,7 @@ protected:
|
|||||||
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_debug_trap(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_debug_trap(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_long_t &packet);
|
||||||
|
MAV_RESULT handle_command_airframe_configuration(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
handle MAV_CMD_CAN_FORWARD and CAN_FRAME messages for CAN over MAVLink
|
handle MAV_CMD_CAN_FORWARD and CAN_FRAME messages for CAN over MAVLink
|
||||||
|
@ -57,6 +57,7 @@
|
|||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||||
#include <AP_KDECAN/AP_KDECAN.h>
|
#include <AP_KDECAN/AP_KDECAN.h>
|
||||||
|
#include <AP_LandingGear/AP_LandingGear.h>
|
||||||
|
|
||||||
#include "MissionItemProtocol_Waypoints.h"
|
#include "MissionItemProtocol_Waypoints.h"
|
||||||
#include "MissionItemProtocol_Rally.h"
|
#include "MissionItemProtocol_Rally.h"
|
||||||
@ -4540,6 +4541,31 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t &
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
|
/*
|
||||||
|
handle MAV_CMD_AIRFRAME_CONFIGURATION for landing gear control
|
||||||
|
*/
|
||||||
|
MAV_RESULT GCS_MAVLINK::handle_command_airframe_configuration(const mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
// Param 1: Select which gear, not used in ArduPilot
|
||||||
|
// Param 2: 0 = Deploy, 1 = Retract
|
||||||
|
// For safety, anything other than 1 will deploy
|
||||||
|
AP_LandingGear *lg = AP_LandingGear::get_singleton();
|
||||||
|
if (lg == nullptr) {
|
||||||
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
}
|
||||||
|
switch ((uint8_t)packet.param2) {
|
||||||
|
case 1:
|
||||||
|
lg->set_position(AP_LandingGear::LandingGear_Retract);
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
default:
|
||||||
|
lg->set_position(AP_LandingGear::LandingGear_Deploy);
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_INS_ACCELCAL_ENABLED
|
#if HAL_INS_ACCELCAL_ENABLED
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
@ -4799,6 +4825,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||||||
result = handle_fixed_mag_cal_yaw(packet);
|
result = handle_fixed_mag_cal_yaw(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
|
case MAV_CMD_AIRFRAME_CONFIGURATION:
|
||||||
|
result = handle_command_airframe_configuration(packet);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
result = MAV_RESULT_UNSUPPORTED;
|
result = MAV_RESULT_UNSUPPORTED;
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user