mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mission: support DO_VTOL_TRANSITION command
first 16 bit command ID
This commit is contained in:
parent
07168c3db4
commit
3a5e4c80ca
@ -727,6 +727,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item
|
||||
copy_location = true;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
cmd.content.do_vtol_transition.target_state = packet.param1;
|
||||
break;
|
||||
|
||||
default:
|
||||
// unrecognised command
|
||||
return MAV_MISSION_UNSUPPORTED;
|
||||
@ -1068,6 +1072,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
||||
copy_location = true;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
packet.param1 = cmd.content.do_vtol_transition.target_state;
|
||||
break;
|
||||
|
||||
default:
|
||||
// unrecognised command
|
||||
return false;
|
||||
|
@ -156,6 +156,11 @@ public:
|
||||
float horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
|
||||
};
|
||||
|
||||
// do VTOL transition
|
||||
struct PACKED Do_VTOL_Transition {
|
||||
uint8_t target_state;
|
||||
};
|
||||
|
||||
union PACKED Content {
|
||||
// jump structure
|
||||
Jump_Command jump;
|
||||
@ -205,6 +210,9 @@ public:
|
||||
// cam trigg distance
|
||||
Altitude_Wait altitude_wait;
|
||||
|
||||
// do vtol transition
|
||||
Do_VTOL_Transition do_vtol_transition;
|
||||
|
||||
// location
|
||||
Location location; // Waypoint location
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user