Sub: AP_WaterDetector -> AP_LeakDetector

This commit is contained in:
Jacob Walser 2017-02-07 14:43:41 -05:00 committed by Andrew Tridgell
parent 88e234272f
commit 56207ac284
6 changed files with 10 additions and 12 deletions

View File

@ -460,7 +460,7 @@ void Sub::dataflash_periodic(void)
// three_hz_loop - 3.3hz loop // three_hz_loop - 3.3hz loop
void Sub::three_hz_loop() void Sub::three_hz_loop()
{ {
set_leak_status(water_detector.update()); set_leak_status(leak_detector.update());
failsafe_internal_pressure_check(); failsafe_internal_pressure_check();

View File

@ -916,10 +916,10 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/AP_GPS/AP_GPS.cpp // @Path: ../libraries/AP_GPS/AP_GPS.cpp
GOBJECT(gps, "GPS_", AP_GPS), GOBJECT(gps, "GPS_", AP_GPS),
// Water driver // Leak detector
// @Group: WD_ // @Group: LEAK_
// @Path: ../libraries/AP_WaterDetector/AP_WaterDetector.cpp // @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp
GOBJECT(water_detector, "WD_", AP_WaterDetector), GOBJECT(leak_detector, "LEAK", AP_LeakDetector),
// @Group: SCHED_ // @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp

View File

@ -390,7 +390,7 @@ public:
k_param_pid_crosstrack_control, k_param_pid_crosstrack_control,
k_param_pid_heading_control, k_param_pid_heading_control,
k_param_water_detector, // water detector object k_param_leak_detector, // leak detector object
k_param_failsafe_leak, // leak failsafe behavior k_param_failsafe_leak, // leak failsafe behavior
k_param_failsafe_pressure, // internal pressure failsafe behavior k_param_failsafe_pressure, // internal pressure failsafe behavior
k_param_failsafe_pressure_max, // maximum internal pressure in pascal before failsafe is triggered k_param_failsafe_pressure_max, // maximum internal pressure in pascal before failsafe is triggered

View File

@ -92,9 +92,7 @@
#include <AP_RPM/AP_RPM.h> #include <AP_RPM/AP_RPM.h>
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library #include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment #include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
#include <AP_WaterDetector/AP_WaterDetector.h> // Water detector #include "../libraries/AP_LeakDetector/AP_LeakDetector.h" // Leak detector
// Configuration
#include "defines.h" #include "defines.h"
#include "config.h" #include "config.h"
@ -171,7 +169,7 @@ private:
AP_GPS gps; AP_GPS gps;
AP_WaterDetector water_detector; AP_LeakDetector leak_detector;
// flight modes convenience array // flight modes convenience array
AP_Int8 *flight_modes; AP_Int8 *flight_modes;

View File

@ -61,4 +61,4 @@ LIBRARIES += AP_IRLock
LIBRARIES += AC_InputManager LIBRARIES += AC_InputManager
LIBRARIES += AP_ADSB LIBRARIES += AP_ADSB
LIBRARIES += AP_JSButton LIBRARIES += AP_JSButton
LIBRARIES += AP_WaterDetector LIBRARIES += AP_LeakDetector

View File

@ -23,6 +23,7 @@ def build(bld):
'AP_InertialNav', 'AP_InertialNav',
'AP_JSButton', 'AP_JSButton',
'AP_LandingGear', 'AP_LandingGear',
'AP_LeakDetector',
'AP_Menu', 'AP_Menu',
'AP_Motors', 'AP_Motors',
'AP_Mount', 'AP_Mount',
@ -32,7 +33,6 @@ def build(bld):
'AP_RSSI', 'AP_RSSI',
'AP_Relay', 'AP_Relay',
'AP_ServoRelayEvents', 'AP_ServoRelayEvents',
'AP_WaterDetector',
], ],
use='mavlink', use='mavlink',
) )