mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
ArduPlane: add build_option.py entry for Plane offboard-guided control
This commit is contained in:
parent
a4a9113cde
commit
74bf618a32
@ -874,12 +874,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com
|
|||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
|
||||||
// these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls.
|
// these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls.
|
||||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
switch(packet.command) {
|
switch(packet.command) {
|
||||||
|
|
||||||
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
|
|
||||||
case MAV_CMD_GUIDED_CHANGE_SPEED: {
|
case MAV_CMD_GUIDED_CHANGE_SPEED: {
|
||||||
// command is only valid in guided mode
|
// command is only valid in guided mode
|
||||||
if (plane.control_mode != &plane.mode_guided) {
|
if (plane.control_mode != &plane.mode_guided) {
|
||||||
@ -1008,14 +1007,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl
|
|||||||
plane.guided_state.target_heading_time_ms = AP_HAL::millis();
|
plane.guided_state.target_heading_time_ms = AP_HAL::millis();
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
// anything else ...
|
// anything else ...
|
||||||
return MAV_RESULT_UNSUPPORTED;
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
@ -1027,11 +1023,13 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||||||
case MAV_CMD_DO_REPOSITION:
|
case MAV_CMD_DO_REPOSITION:
|
||||||
return handle_command_int_do_reposition(packet);
|
return handle_command_int_do_reposition(packet);
|
||||||
|
|
||||||
|
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
|
||||||
// special 'slew-enabled' guided commands here... for speed,alt, and direction commands
|
// special 'slew-enabled' guided commands here... for speed,alt, and direction commands
|
||||||
case MAV_CMD_GUIDED_CHANGE_SPEED:
|
case MAV_CMD_GUIDED_CHANGE_SPEED:
|
||||||
case MAV_CMD_GUIDED_CHANGE_ALTITUDE:
|
case MAV_CMD_GUIDED_CHANGE_ALTITUDE:
|
||||||
case MAV_CMD_GUIDED_CHANGE_HEADING:
|
case MAV_CMD_GUIDED_CHANGE_HEADING:
|
||||||
return handle_command_int_guided_slew_commands(packet);
|
return handle_command_int_guided_slew_commands(packet);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
|
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
|
||||||
case MAV_CMD_DO_FOLLOW:
|
case MAV_CMD_DO_FOLLOW:
|
||||||
|
Loading…
Reference in New Issue
Block a user