mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Add AP_Arming_Sub class
This commit is contained in:
parent
abcc75009d
commit
d21cd513cd
7
ArduSub/AP_Arming_Sub.cpp
Normal file
7
ArduSub/AP_Arming_Sub.cpp
Normal file
@ -0,0 +1,7 @@
|
||||
#include "AP_Arming_Sub.h"
|
||||
#include "Sub.h"
|
||||
|
||||
enum HomeState AP_Arming_Sub::home_status() const
|
||||
{
|
||||
return sub.ap.home_state;
|
||||
}
|
15
ArduSub/AP_Arming_Sub.h
Normal file
15
ArduSub/AP_Arming_Sub.h
Normal file
@ -0,0 +1,15 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
|
||||
class AP_Arming_Sub : public AP_Arming {
|
||||
public:
|
||||
AP_Arming_Sub(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||
const AP_BattMonitor &battery) :
|
||||
AP_Arming(ahrs_ref, baro, compass, battery) {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
protected:
|
||||
enum HomeState home_status() const override;
|
||||
};
|
@ -353,14 +353,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
||||
#endif
|
||||
|
||||
// @Param: ARMING_CHECK
|
||||
// @DisplayName: Arming check
|
||||
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer, compass and GPS
|
||||
// @Values: 0:Disabled, 1:Enabled, -3:Skip Baro, -5:Skip Compass, -9:Skip GPS, -17:Skip INS, -33:Skip Params/Rangefinder, -65:Skip RC, 127:Skip Voltage
|
||||
// @Bitmask: 0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Rangefinder,6:RC,7:Voltage
|
||||
// @User: Standard
|
||||
GSCALAR(arming_check, "ARMING_CHECK", ARMING_CHECK_NONE),
|
||||
|
||||
// @Param: DISARM_DELAY
|
||||
// @DisplayName: Disarm delay
|
||||
// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
|
||||
@ -746,6 +738,10 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
||||
GOBJECT(battery, "BATT", AP_BattMonitor),
|
||||
|
||||
// @Group: ARMING_
|
||||
// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp
|
||||
GOBJECT(arming, "ARMING_", AP_Arming_Sub),
|
||||
|
||||
// @Group: BRD_
|
||||
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
|
||||
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
|
||||
@ -958,6 +954,14 @@ void Sub::load_parameters(void)
|
||||
|
||||
AP_Param::set_default_by_name("BRD_SAFETYENABLE", 0);
|
||||
AP_Param::set_default_by_name("GND_EXT_BUS", 1);
|
||||
AP_Param::set_default_by_name("ARMING_CHECK",
|
||||
AP_Arming::ARMING_CHECK_BARO |
|
||||
AP_Arming::ARMING_CHECK_COMPASS |
|
||||
AP_Arming::ARMING_CHECK_INS |
|
||||
AP_Arming::ARMING_CHECK_RC |
|
||||
AP_Arming::ARMING_CHECK_VOLTAGE |
|
||||
AP_Arming::ARMING_CHECK_BATTERY |
|
||||
AP_Arming::ARMING_CHECK_LOGGING);
|
||||
}
|
||||
|
||||
void Sub::convert_old_parameters(void)
|
||||
|
@ -69,6 +69,7 @@ public:
|
||||
k_param_serial_manager, // Serial ports, AP_SerialManager
|
||||
k_param_notify, // Notify Library, AP_Notify
|
||||
k_param_cli_enabled, // Old (deprecated) command line interface
|
||||
k_param_arming, // Arming checks
|
||||
|
||||
|
||||
// Sensor objects
|
||||
@ -185,7 +186,7 @@ public:
|
||||
|
||||
// Misc Sub settings
|
||||
k_param_log_bitmask = 165,
|
||||
k_param_arming_check,
|
||||
k_param_arming_check, // deprecated, remove
|
||||
k_param_angle_max,
|
||||
k_param_rangefinder_gain,
|
||||
k_param_gps_hdop_good,
|
||||
@ -310,7 +311,6 @@ public:
|
||||
AP_Int8 ch10_option;
|
||||
AP_Int8 ch11_option;
|
||||
AP_Int8 ch12_option;
|
||||
AP_Int8 arming_check;
|
||||
AP_Int8 disarm_delay;
|
||||
|
||||
AP_Int8 fs_ekf_action;
|
||||
|
@ -83,6 +83,7 @@
|
||||
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
|
||||
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
|
||||
#include <AP_TemperatureSensor/TSYS01.h>
|
||||
#include "AP_Arming_Sub.h"
|
||||
#include "defines.h"
|
||||
#include "config.h"
|
||||
|
||||
@ -121,6 +122,7 @@ public:
|
||||
friend class GCS_MAVLINK_Sub;
|
||||
friend class Parameters;
|
||||
friend class ParametersG2;
|
||||
friend class AP_Arming_Sub;
|
||||
|
||||
Sub(void);
|
||||
|
||||
@ -349,6 +351,8 @@ private:
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery;
|
||||
|
||||
AP_Arming_Sub arming {ahrs, barometer, compass, battery};
|
||||
|
||||
// Altitude
|
||||
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
||||
int16_t climb_rate;
|
||||
|
@ -56,3 +56,4 @@ LIBRARIES += AP_LeakDetector
|
||||
LIBRARIES += AP_Gripper
|
||||
LIBRARIES += AP_Beacon
|
||||
LIBRARIES += AP_TemperatureSensor
|
||||
LIBRARIES += AP_Arming
|
||||
|
@ -25,7 +25,8 @@ def build(bld):
|
||||
'AP_Proximity',
|
||||
'AP_Gripper',
|
||||
'AP_Beacon',
|
||||
'AP_TemperatureSensor'
|
||||
'AP_TemperatureSensor',
|
||||
'AP_Arming'
|
||||
],
|
||||
)
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user