mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: add option to disable GUIDED flight mode
Saves about 6kB of flash
This commit is contained in:
parent
0ddeb56a05
commit
b8c432b1a1
@ -25,6 +25,7 @@
|
|||||||
//#define WINCH_ENABLED DISABLED // disable winch support
|
//#define WINCH_ENABLED DISABLED // disable winch support
|
||||||
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
|
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
|
||||||
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
|
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
|
||||||
|
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
|
||||||
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
|
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
|
||||||
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
|
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
|
||||||
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
|
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
|
||||||
|
@ -968,7 +968,9 @@ private:
|
|||||||
ModeDrift mode_drift;
|
ModeDrift mode_drift;
|
||||||
#endif
|
#endif
|
||||||
ModeFlip mode_flip;
|
ModeFlip mode_flip;
|
||||||
|
#if MODE_GUIDED_ENABLED == ENABLED
|
||||||
ModeGuided mode_guided;
|
ModeGuided mode_guided;
|
||||||
|
#endif
|
||||||
ModeLand mode_land;
|
ModeLand mode_land;
|
||||||
#if MODE_LOITER_ENABLED == ENABLED
|
#if MODE_LOITER_ENABLED == ENABLED
|
||||||
ModeLoiter mode_loiter;
|
ModeLoiter mode_loiter;
|
||||||
|
@ -1341,6 +1341,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if MODE_GUIDED_ENABLED == ENABLED
|
||||||
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: // MAV ID: 82
|
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: // MAV ID: 82
|
||||||
{
|
{
|
||||||
// decode packet
|
// decode packet
|
||||||
@ -1581,6 +1582,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
|
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
|
||||||
{
|
{
|
||||||
|
@ -279,6 +279,12 @@
|
|||||||
# define MODE_DRIFT_ENABLED ENABLED
|
# define MODE_DRIFT_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Guided mode - control vehicle's position or angles from GCS
|
||||||
|
#ifndef MODE_GUIDED_ENABLED
|
||||||
|
# define MODE_GUIDED_ENABLED ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Loiter mode - allows vehicle to hold global position
|
// Loiter mode - allows vehicle to hold global position
|
||||||
#ifndef MODE_LOITER_ENABLED
|
#ifndef MODE_LOITER_ENABLED
|
||||||
@ -616,6 +622,10 @@
|
|||||||
#error AC_Avoidance relies on AC_FENCE which is disabled
|
#error AC_Avoidance relies on AC_FENCE which is disabled
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED
|
||||||
|
#error ModeAuto requires ModeGuided which is disabled
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Developer Items
|
// Developer Items
|
||||||
//
|
//
|
||||||
|
@ -66,9 +66,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if MODE_GUIDED_ENABLED == ENABLED
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
ret = &mode_guided;
|
ret = &mode_guided;
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case LAND:
|
case LAND:
|
||||||
ret = &mode_land;
|
ret = &mode_land;
|
||||||
|
@ -36,12 +36,14 @@ bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
switch(control_mode) {
|
switch(control_mode) {
|
||||||
|
#if MODE_GUIDED_ENABLED == ENABLED
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
if (mode_guided.takeoff_start(takeoff_alt_cm)) {
|
if (mode_guided.takeoff_start(takeoff_alt_cm)) {
|
||||||
set_auto_armed(true);
|
set_auto_armed(true);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
#endif
|
||||||
case LOITER:
|
case LOITER:
|
||||||
case POSHOLD:
|
case POSHOLD:
|
||||||
case ALT_HOLD:
|
case ALT_HOLD:
|
||||||
|
Loading…
Reference in New Issue
Block a user