mirror of https://github.com/ArduPilot/ardupilot
Sub: Disable RPM
This commit is contained in:
parent
57013583ac
commit
ee8670e73d
|
@ -123,7 +123,9 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
SCHED_TASK(full_rate_logging_loop,400, 100),
|
||||
SCHED_TASK(dataflash_periodic, 400, 300),
|
||||
SCHED_TASK(perf_update, 0.1, 75),
|
||||
#if RPM_ENABLED == ENABLED
|
||||
SCHED_TASK(rpm_update, 10, 200),
|
||||
#endif
|
||||
SCHED_TASK(compass_cal_update, 100, 100),
|
||||
SCHED_TASK(accel_cal_update, 10, 100),
|
||||
SCHED_TASK(terrain_update, 10, 100),
|
||||
|
|
|
@ -438,6 +438,7 @@ void NOINLINE Sub::send_rangefinder(mavlink_channel_t chan)
|
|||
/*
|
||||
send RPM packet
|
||||
*/
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void NOINLINE Sub::send_rpm(mavlink_channel_t chan)
|
||||
{
|
||||
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
|
||||
|
@ -447,6 +448,7 @@ void NOINLINE Sub::send_rpm(mavlink_channel_t chan)
|
|||
rpm_sensor.get_rpm(1));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
|
@ -652,8 +654,10 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||
break;
|
||||
|
||||
case MSG_RPM:
|
||||
#if RPM_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
sub.send_rpm(chan);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSG_TERRAIN:
|
||||
|
@ -1001,7 +1005,9 @@ GCS_MAVLINK::data_stream_send(void)
|
|||
send_message(MSG_MAG_CAL_PROGRESS);
|
||||
send_message(MSG_EKF_STATUS_REPORT);
|
||||
send_message(MSG_VIBRATION);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
send_message(MSG_RPM);
|
||||
#endif
|
||||
}
|
||||
|
||||
if (sub.gcs_out_of_time) return;
|
||||
|
|
|
@ -996,9 +996,11 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
GOBJECT(optflow, "FLOW", OpticalFlow),
|
||||
#endif
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
// @Group: RPM
|
||||
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
|
||||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
#endif
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
// @Param: AUTOTUNE_AXES
|
||||
|
|
|
@ -86,7 +86,9 @@
|
|||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#if RPM_ENABLED == ENABLED
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
#endif
|
||||
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
||||
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
|
||||
#include "../libraries/AP_LeakDetector/AP_LeakDetector.h" // Leak detector
|
||||
|
@ -175,7 +177,9 @@ private:
|
|||
LowPassFilterFloat alt_cm_filt; // altitude filter
|
||||
} rangefinder_state = { false, false, 0, 0 };
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
AP_RPM rpm_sensor;
|
||||
#endif
|
||||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF EKF{&ahrs, barometer, rangefinder};
|
||||
|
@ -556,8 +560,10 @@ private:
|
|||
void send_vfr_hud(mavlink_channel_t chan);
|
||||
void send_current_waypoint(mavlink_channel_t chan);
|
||||
void send_rangefinder(mavlink_channel_t chan);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void rpm_update();
|
||||
#endif
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void gcs_send_message(enum ap_message id);
|
||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||
|
|
|
@ -86,6 +86,14 @@
|
|||
# define RC_FAST_SPEED 490
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RPM
|
||||
//
|
||||
|
||||
#ifndef RPM_ENABLED
|
||||
# define RPM_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Rangefinder
|
||||
//
|
||||
|
|
|
@ -84,6 +84,7 @@ bool Sub::rangefinder_alt_ok()
|
|||
/*
|
||||
update RPM sensors
|
||||
*/
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void Sub::rpm_update(void)
|
||||
{
|
||||
rpm_sensor.update();
|
||||
|
@ -93,6 +94,7 @@ void Sub::rpm_update(void)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// initialise compass
|
||||
void Sub::init_compass()
|
||||
|
|
|
@ -250,7 +250,9 @@ void Sub::init_ardupilot()
|
|||
#endif
|
||||
|
||||
// initialise AP_RPM library
|
||||
#if RPM_ENABLED == ENABLED
|
||||
rpm_sensor.init();
|
||||
#endif
|
||||
|
||||
// initialise mission library
|
||||
mission.init();
|
||||
|
|
Loading…
Reference in New Issue