mirror of https://github.com/ArduPilot/ardupilot
ArduSub: add and use AP_RPM_ENABLED
This commit is contained in:
parent
9c7e1c3af9
commit
48308b8156
|
@ -95,7 +95,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57),
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60),
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63),
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#if AP_RPM_ENABLED
|
||||
SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66),
|
||||
#endif
|
||||
SCHED_TASK(terrain_update, 10, 100, 72),
|
||||
|
|
|
@ -387,7 +387,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||
MSG_MAG_CAL_PROGRESS,
|
||||
MSG_EKF_STATUS_REPORT,
|
||||
MSG_VIBRATION,
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#if AP_RPM_ENABLED
|
||||
MSG_RPM,
|
||||
#endif
|
||||
MSG_ESC_TELEMETRY,
|
||||
|
|
|
@ -599,7 +599,7 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
|
||||
#endif
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#if AP_RPM_ENABLED
|
||||
// @Group: RPM
|
||||
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
|
||||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
|
|
|
@ -81,7 +81,9 @@
|
|||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||
#endif
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#include <AP_RPM/AP_RPM_config.h>
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
#endif
|
||||
|
||||
|
@ -151,7 +153,7 @@ private:
|
|||
LowPassFilterFloat alt_cm_filt; // altitude filter
|
||||
} rangefinder_state = { false, false, 0, 0 };
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#if AP_RPM_ENABLED
|
||||
AP_RPM rpm_sensor;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -34,14 +34,6 @@
|
|||
# define CIRCLE_NAV_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RPM
|
||||
//
|
||||
|
||||
#ifndef RPM_ENABLED
|
||||
# define RPM_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RCMAP
|
||||
//
|
||||
|
|
|
@ -137,7 +137,7 @@ void Sub::init_ardupilot()
|
|||
#endif
|
||||
|
||||
// initialise AP_RPM library
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#if AP_RPM_ENABLED
|
||||
rpm_sensor.init();
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue