mirror of https://github.com/ArduPilot/ardupilot
Copter: Change external button specification to option
Copter: Change the definition name from BUTTON to BUTTON_ENABLED.
This commit is contained in:
parent
a34b135a57
commit
bd1a56236b
|
@ -46,6 +46,7 @@
|
||||||
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
|
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
|
||||||
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
|
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
|
||||||
//#define OSD_ENABLED DISABLED // disable on-screen-display support
|
//#define OSD_ENABLED DISABLED // disable on-screen-display support
|
||||||
|
//#define BUTTON_ENABLED DISABLED // disable button support
|
||||||
|
|
||||||
|
|
||||||
// features below are disabled by default on all boards
|
// features below are disabled by default on all boards
|
||||||
|
|
|
@ -196,7 +196,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||||
#ifdef USERHOOK_SUPERSLOWLOOP
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||||
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
|
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
|
||||||
#endif
|
#endif
|
||||||
|
#if BUTTON_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Button, &copter.g2.button, update, 5, 100),
|
SCHED_TASK_CLASS(AP_Button, &copter.g2.button, update, 5, 100),
|
||||||
|
#endif
|
||||||
#if STATS_ENABLED == ENABLED
|
#if STATS_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100),
|
SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100),
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -72,7 +72,6 @@
|
||||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||||
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
||||||
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
|
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
|
||||||
#include <AP_Button/AP_Button.h>
|
|
||||||
#include <AP_Arming/AP_Arming.h>
|
#include <AP_Arming/AP_Arming.h>
|
||||||
#include <AP_SmartRTL/AP_SmartRTL.h>
|
#include <AP_SmartRTL/AP_SmartRTL.h>
|
||||||
#include <AP_TempCalibration/AP_TempCalibration.h>
|
#include <AP_TempCalibration/AP_TempCalibration.h>
|
||||||
|
@ -156,6 +155,9 @@
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
# include <AP_Camera/AP_Camera.h>
|
# include <AP_Camera/AP_Camera.h>
|
||||||
#endif
|
#endif
|
||||||
|
#if BUTTON_ENABLED == ENABLED
|
||||||
|
# include <AP_Button/AP_Button.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
#if OSD_ENABLED == ENABLED
|
#if OSD_ENABLED == ENABLED
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
|
@ -553,6 +555,11 @@ private:
|
||||||
AP_Parachute parachute{relay};
|
AP_Parachute parachute{relay};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Button
|
||||||
|
#if BUTTON_ENABLED == ENABLED
|
||||||
|
AP_Button button;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Landing Gear Controller
|
// Landing Gear Controller
|
||||||
AP_LandingGear landinggear;
|
AP_LandingGear landinggear;
|
||||||
|
|
||||||
|
|
|
@ -732,9 +732,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0),
|
AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0),
|
||||||
|
|
||||||
|
#if BUTTON_ENABLED == ENABLED
|
||||||
// @Group: BTN_
|
// @Group: BTN_
|
||||||
// @Path: ../libraries/AP_Button/AP_Button.cpp
|
// @Path: ../libraries/AP_Button/AP_Button.cpp
|
||||||
AP_SUBGROUPINFO(button, "BTN_", 2, ParametersG2, AP_Button),
|
AP_SUBGROUPINFO(button, "BTN_", 2, ParametersG2, AP_Button),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
// @Param: THROW_NEXTMODE
|
// @Param: THROW_NEXTMODE
|
||||||
|
|
|
@ -485,8 +485,10 @@ public:
|
||||||
// altitude at which nav control can start in takeoff
|
// altitude at which nav control can start in takeoff
|
||||||
AP_Float wp_navalt_min;
|
AP_Float wp_navalt_min;
|
||||||
|
|
||||||
|
#if BUTTON_ENABLED == ENABLED
|
||||||
// button checking
|
// button checking
|
||||||
AP_Button button;
|
AP_Button button;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if STATS_ENABLED == ENABLED
|
#if STATS_ENABLED == ENABLED
|
||||||
// vehicle statistics
|
// vehicle statistics
|
||||||
|
|
|
@ -371,6 +371,12 @@
|
||||||
# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
|
# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Button - Enable the button connected to AUX1-6
|
||||||
|
#ifndef BUTTON_ENABLED
|
||||||
|
# define BUTTON_ENABLED ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// RADIO CONFIGURATION
|
// RADIO CONFIGURATION
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
Loading…
Reference in New Issue