ArduCopter: add and use AP_RPM_ENABLED

This commit is contained in:
Peter Barker 2022-07-16 09:59:12 +10:00 committed by Andrew Tridgell
parent 4b8ab9d8a9
commit 9c7e1c3af9
6 changed files with 5 additions and 14 deletions

View File

@ -17,7 +17,6 @@
//#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support
//#define GRIPPER_ENABLED DISABLED // disable gripper support
//#define RPM_ENABLED DISABLED // disable rotations per minute sensor support
//#define STATS_ENABLED DISABLED // disable statistics support
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support

View File

@ -214,7 +214,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50, 123),
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126),
#if RPM_ENABLED == ENABLED
#if AP_RPM_ENABLED
SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129),
#endif
SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135),

View File

@ -149,9 +149,7 @@
#if WINCH_ENABLED == ENABLED
# include <AP_Winch/AP_Winch.h>
#endif
#if RPM_ENABLED == ENABLED
#include <AP_RPM/AP_RPM.h>
#endif
#include <AP_RPM/AP_RPM.h>
#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
@ -302,7 +300,7 @@ private:
bool reset_target; // true if target should be reset because of change in surface being tracked
} surface_tracking;
#if RPM_ENABLED == ENABLED
#if AP_RPM_ENABLED
AP_RPM rpm_sensor;
#endif

View File

@ -683,7 +683,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(precland, "PLND_", AC_PrecLand),
#endif
#if RPM_ENABLED == ENABLED
#if AP_RPM_ENABLED
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),

View File

@ -193,12 +193,6 @@
# define WINCH_ENABLED !HAL_MINIMIZE_FEATURES
#endif
//////////////////////////////////////////////////////////////////////////////
// rotations per minute sensor support
#ifndef RPM_ENABLED
# define RPM_ENABLED !HAL_MINIMIZE_FEATURES
#endif
//////////////////////////////////////////////////////////////////////////////
// Parachute release
#ifndef PARACHUTE

View File

@ -159,7 +159,7 @@ void Copter::init_ardupilot()
g2.beacon.init();
#endif
#if RPM_ENABLED == ENABLED
#if AP_RPM_ENABLED
// initialise AP_RPM library
rpm_sensor.init();
#endif