Copter: add option to disable CIRCLE flight mode

Saves about 2.4kB of flash
This commit is contained in:
Peter Barker 2018-02-23 20:51:17 +11:00 committed by Randy Mackay
parent e4898e1d60
commit 5b355214fd
8 changed files with 27 additions and 0 deletions

View File

@ -25,6 +25,7 @@
//#define WINCH_ENABLED DISABLED // disable winch support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support

View File

@ -485,7 +485,9 @@ private:
AC_AttitudeControl_t *attitude_control;
AC_PosControl *pos_control;
AC_WPNav *wp_nav;
#if MODE_CIRCLE_ENABLED == ENABLED
AC_Circle *circle_nav;
#endif
// System Timers
// --------------
@ -965,7 +967,9 @@ private:
#if MODE_BRAKE_ENABLED == ENABLED
ModeBrake mode_brake;
#endif
#if MODE_CIRCLE_ENABLED == ENABLED
ModeCircle mode_circle;
#endif
#if MODE_DRIFT_ENABLED == ENABLED
ModeDrift mode_drift;
#endif

View File

@ -602,9 +602,11 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),
#if MODE_CIRCLE_ENABLED == ENABLED
// @Group: CIRCLE_
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
#endif
// @Group: ATC_
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp

View File

@ -279,6 +279,12 @@
# define MODE_BRAKE_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Circle - fly vehicle around a central point
#ifndef MODE_CIRCLE_ENABLED
# define MODE_CIRCLE_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Drift - fly vehicle in altitude-held, coordinated-turn mode
#ifndef MODE_DRIFT_ENABLED
@ -644,6 +650,10 @@
#error ModeAuto requires ModeGuided which is disabled
#endif
#if MODE_AUTO_ENABLED && !MODE_CIRCLE_ENABLED
#error ModeAuto requires ModeCircle which is disabled
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//

View File

@ -56,9 +56,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
break;
#endif
#if MODE_CIRCLE_ENABLED == ENABLED
case CIRCLE:
ret = &mode_circle;
break;
#endif
#if MODE_LOITER_ENABLED == ENABLED
case LOITER:

View File

@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_CIRCLE_ENABLED == ENABLED
/*
* Init and run calls for circle flight mode
*/
@ -103,3 +105,5 @@ int32_t Copter::ModeCircle::wp_bearing() const
{
return wp_nav->get_loiter_bearing_to_target();
}
#endif

View File

@ -615,11 +615,13 @@ void Copter::allocate_motors(void)
}
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
#if MODE_CIRCLE_ENABLED == ENABLED
circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
if (circle_nav == nullptr) {
AP_HAL::panic("Unable to allocate CircleNav");
}
AP_Param::load_object_from_eeprom(circle_nav, circle_nav->var_info);
#endif
// reload lines from the defaults file that may now be accessible
AP_Param::reload_defaults_file();

View File

@ -133,10 +133,12 @@ void Copter::tuning() {
compass.set_declination(ToRad((2.0f * control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
break;
#if MODE_CIRCLE_ENABLED == ENABLED
case TUNING_CIRCLE_RATE:
// set circle rate up to approximately 45 deg/sec in either direction
circle_nav->set_rate((float)control_in/25.0f-20.0f);
break;
#endif
case TUNING_RANGEFINDER_GAIN:
// set rangefinder gain