Browse Source

Copter: add option to disable SmartRTL mode

Saves 5.5k of Flash
mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
9b440d6b25
  1. 2
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/ArduCopter.cpp
  3. 2
      ArduCopter/Copter.h
  4. 5
      ArduCopter/Parameters.cpp
  5. 2
      ArduCopter/Parameters.h
  6. 4
      ArduCopter/commands.cpp
  7. 6
      ArduCopter/config.h
  8. 4
      ArduCopter/mode.cpp
  9. 4
      ArduCopter/mode_smart_rtl.cpp
  10. 2
      ArduCopter/motors.cpp
  11. 2
      ArduCopter/system.cpp

2
ArduCopter/APM_Config.h

@ -25,6 +25,8 @@
//#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_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
// features below are disabled by default on all boards // features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes

2
ArduCopter/ArduCopter.cpp

@ -106,7 +106,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(update_altitude, 10, 100), SCHED_TASK(update_altitude, 10, 100),
SCHED_TASK(run_nav_updates, 50, 100), SCHED_TASK(run_nav_updates, 50, 100),
SCHED_TASK(update_throttle_hover,100, 90), SCHED_TASK(update_throttle_hover,100, 90),
#if MODE_SMARTRTL_ENABLED == ENABLED
SCHED_TASK_CLASS(Copter::ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100), SCHED_TASK_CLASS(Copter::ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100),
#endif
SCHED_TASK(three_hz_loop, 3, 75), SCHED_TASK(three_hz_loop, 3, 75),
SCHED_TASK(compass_accumulate, 100, 100), SCHED_TASK(compass_accumulate, 100, 100),
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90),

2
ArduCopter/Copter.h

@ -984,7 +984,9 @@ private:
#endif #endif
ModeThrow mode_throw; ModeThrow mode_throw;
ModeGuidedNoGPS mode_guided_nogps; ModeGuidedNoGPS mode_guided_nogps;
#if MODE_SMARTRTL_ENABLED == ENABLED
ModeSmartRTL mode_smartrtl; ModeSmartRTL mode_smartrtl;
#endif
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
ModeFlowHold mode_flowhold; ModeFlowHold mode_flowhold;
#endif #endif

5
ArduCopter/Parameters.cpp

@ -944,9 +944,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode), AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode),
#endif #endif
#if MODE_SMARTRTL_ENABLED == ENABLED
// @Group: SRTL_ // @Group: SRTL_
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp // @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL), AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),
#endif
#if WINCH_ENABLED == ENABLED #if WINCH_ENABLED == ENABLED
// @Group: WENC // @Group: WENC
@ -997,8 +999,9 @@ ParametersG2::ParametersG2(void)
#if ADVANCED_FAILSAFE == ENABLED #if ADVANCED_FAILSAFE == ENABLED
,afs(copter.mission, copter.barometer, copter.gps, copter.rcmap) ,afs(copter.mission, copter.barometer, copter.gps, copter.rcmap)
#endif #endif
#if MODE_SMARTRTL_ENABLED == ENABLED
,smart_rtl(copter.ahrs) ,smart_rtl(copter.ahrs)
,temp_calibration(copter.barometer, copter.ins) #endif
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
,mode_flowhold_ptr(&copter.mode_flowhold) ,mode_flowhold_ptr(&copter.mode_flowhold)
#endif #endif

2
ArduCopter/Parameters.h

@ -549,8 +549,10 @@ public:
// control over servo output ranges // control over servo output ranges
SRV_Channels servo_channels; SRV_Channels servo_channels;
#if MODE_SMARTRTL_ENABLED == ENABLED
// Safe RTL library // Safe RTL library
AP_SmartRTL smart_rtl; AP_SmartRTL smart_rtl;
#endif
// wheel encoder and winch // wheel encoder and winch
#if WINCH_ENABLED == ENABLED #if WINCH_ENABLED == ENABLED

4
ArduCopter/commands.cpp

@ -35,7 +35,9 @@ void Copter::set_home_to_current_location_inflight() {
return; return;
} }
// we have successfully set AHRS home, set it for SmartRTL // we have successfully set AHRS home, set it for SmartRTL
#if MODE_SMARTRTL_ENABLED == ENABLED
g2.smart_rtl.set_home(true); g2.smart_rtl.set_home(true);
#endif
} }
} }
@ -48,7 +50,9 @@ bool Copter::set_home_to_current_location(bool lock) {
return false; return false;
} }
// we have successfully set AHRS home, set it for SmartRTL // we have successfully set AHRS home, set it for SmartRTL
#if MODE_SMARTRTL_ENABLED == ENABLED
g2.smart_rtl.set_home(true); g2.smart_rtl.set_home(true);
#endif
return true; return true;
} }
return false; return false;

6
ArduCopter/config.h

@ -279,6 +279,12 @@
# define MODE_POSHOLD_ENABLED ENABLED # define MODE_POSHOLD_ENABLED ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home
#ifndef MODE_SMARTRTL_ENABLED
# define MODE_SMARTRTL_ENABLED ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION // RADIO CONFIGURATION
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////

4
ArduCopter/mode.cpp

@ -118,9 +118,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
ret = &mode_guided_nogps; ret = &mode_guided_nogps;
break; break;
#if MODE_SMARTRTL_ENABLED == ENABLED
case SMART_RTL: case SMART_RTL:
ret = &mode_smartrtl; ret = &mode_smartrtl;
break; break;
#endif
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
case FLOWHOLD: case FLOWHOLD:
@ -249,10 +251,12 @@ void Copter::exit_mode(Copter::Mode *&old_flightmode,
// cancel any takeoffs in progress // cancel any takeoffs in progress
takeoff_stop(); takeoff_stop();
#if MODE_SMARTRTL_ENABLED == ENABLED
// call smart_rtl cleanup // call smart_rtl cleanup
if (old_flightmode == &mode_smartrtl) { if (old_flightmode == &mode_smartrtl) {
mode_smartrtl.exit(); mode_smartrtl.exit();
} }
#endif
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// firmly reset the flybar passthrough to false when exiting acro mode. // firmly reset the flybar passthrough to false when exiting acro mode.

4
ArduCopter/mode_smart_rtl.cpp

@ -1,5 +1,7 @@
#include "Copter.h" #include "Copter.h"
#if MODE_SMARTRTL_ENABLED == ENABLED
/* /*
* Init and run calls for Smart_RTL flight mode * Init and run calls for Smart_RTL flight mode
* *
@ -147,3 +149,5 @@ int32_t Copter::ModeSmartRTL::wp_bearing() const
{ {
return wp_nav->get_wp_bearing_to_destination(); return wp_nav->get_wp_bearing_to_destination();
} }
#endif

2
ArduCopter/motors.cpp

@ -193,7 +193,9 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
update_super_simple_bearing(false); update_super_simple_bearing(false);
// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point // Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
#if MODE_SMARTRTL_ENABLED == ENABLED
g2.smart_rtl.set_home(position_ok()); g2.smart_rtl.set_home(position_ok());
#endif
// enable gps velocity based centrefugal force compensation // enable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(true); ahrs.set_correct_centrifugal(true);

2
ArduCopter/system.cpp

@ -236,8 +236,10 @@ void Copter::init_ardupilot()
mission.init(); mission.init();
#endif #endif
#if MODE_SMARTRTL_ENABLED == ENABLED
// initialize SmartRTL // initialize SmartRTL
g2.smart_rtl.init(); g2.smart_rtl.init();
#endif
// initialise DataFlash library // initialise DataFlash library
#if MODE_AUTO_ENABLED == ENABLED #if MODE_AUTO_ENABLED == ENABLED

Loading…
Cancel
Save