mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: allow Plane to run MAV_CMD_MISSION_START as long and int
This commit is contained in:
parent
ce1bb64686
commit
2e494d496b
@ -1010,6 +1010,10 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||||||
}
|
}
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
|
||||||
|
case MAV_CMD_MISSION_START:
|
||||||
|
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||||
}
|
}
|
||||||
@ -1057,10 +1061,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||||||
}
|
}
|
||||||
#endif // HAL_QUADPLANE_ENABLED
|
#endif // HAL_QUADPLANE_ENABLED
|
||||||
|
|
||||||
case MAV_CMD_MISSION_START:
|
|
||||||
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user