mirror of https://github.com/ArduPilot/ardupilot
Rover: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
81adafa97c
commit
4b8ab9d8a9
|
@ -357,9 +357,11 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
#endif
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
// @Group: RPM
|
||||
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
|
||||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
#endif
|
||||
|
||||
// @Group: MIS_
|
||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||
|
|
|
@ -98,7 +98,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
SCHED_TASK(update_precland, 400, 50, 70),
|
||||
#endif
|
||||
#endif
|
||||
#if AP_RPM_ENABLED
|
||||
SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),
|
||||
#endif
|
||||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
|
||||
#endif
|
||||
|
|
|
@ -129,8 +129,10 @@ private:
|
|||
AP_Int8 *modes;
|
||||
const uint8_t num_modes = 6;
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
// AP_RPM Module
|
||||
AP_RPM rpm_sensor;
|
||||
#endif
|
||||
|
||||
// Arming/Disarming management class
|
||||
AP_Arming_Rover arming;
|
||||
|
|
|
@ -35,8 +35,10 @@ void Rover::init_ardupilot()
|
|||
|
||||
battery.init();
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
// Initialise RPM sensor
|
||||
rpm_sensor.init();
|
||||
#endif
|
||||
|
||||
rssi.init();
|
||||
|
||||
|
|
Loading…
Reference in New Issue