mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Remove sprayer
This commit is contained in:
parent
9503e8d140
commit
7e1c63aba3
@ -32,7 +32,6 @@
|
||||
#define TRANSECT_ENABLED DISABLED
|
||||
|
||||
// features below are disabled by default on all boards
|
||||
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||
|
||||
// other settings
|
||||
|
@ -465,10 +465,6 @@ void Sub::three_hz_loop()
|
||||
fence_check();
|
||||
#endif // AC_FENCE_ENABLED
|
||||
|
||||
#if SPRAYER == ENABLED
|
||||
sprayer.update();
|
||||
#endif
|
||||
|
||||
update_events();
|
||||
|
||||
// update ch6 in flight tuning
|
||||
|
@ -922,12 +922,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
|
||||
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
|
||||
|
||||
#if SPRAYER == ENABLED
|
||||
// @Group: SPRAY_
|
||||
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
|
||||
GOBJECT(sprayer, "SPRAY_", AC_Sprayer),
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
GOBJECT(sitl, "SIM_", SITL::SITL),
|
||||
#endif
|
||||
|
@ -84,7 +84,6 @@ public:
|
||||
k_param_rangefinder_gain,
|
||||
k_param_ch8_option,
|
||||
k_param_arming_check,
|
||||
k_param_sprayer,
|
||||
k_param_angle_max,
|
||||
k_param_gps_hdop_good,
|
||||
k_param_battery,
|
||||
|
@ -88,9 +88,6 @@ Sub::Sub(void) :
|
||||
#if AC_RALLY == ENABLED
|
||||
rally(ahrs),
|
||||
#endif
|
||||
#if SPRAYER == ENABLED
|
||||
sprayer(&inertial_nav),
|
||||
#endif
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
terrain(ahrs, mission, rally),
|
||||
#endif
|
||||
|
@ -97,9 +97,6 @@
|
||||
#include "GCS_Mavlink.h"
|
||||
|
||||
// libraries which are dependent on #defines in defines.h and/or config.h
|
||||
#if SPRAYER == ENABLED
|
||||
#include <AC_Sprayer/AC_Sprayer.h> // crop sprayer library
|
||||
#endif
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
|
||||
#endif
|
||||
@ -481,12 +478,7 @@ private:
|
||||
#endif
|
||||
|
||||
// RSSI
|
||||
AP_RSSI rssi;
|
||||
|
||||
// Crop Sprayer
|
||||
#if SPRAYER == ENABLED
|
||||
AC_Sprayer sprayer;
|
||||
#endif
|
||||
AP_RSSI rssi;
|
||||
|
||||
// terrain handling
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
|
@ -51,7 +51,10 @@ enum aux_sw_func {
|
||||
AUXSW_RESETTOARMEDYAW = 12, // changes yaw to be same as when quad was armed
|
||||
AUXSW_SUPERSIMPLE_MODE = 13, // change to simple mode in middle, super simple at top
|
||||
AUXSW_ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
|
||||
AUXSW_SPRAYER = 15, // enable/disable the crop sprayer
|
||||
|
||||
// No sprayer for Sub, remove
|
||||
// AUXSW_SPRAYER = 15, // enable/disable the crop sprayer
|
||||
|
||||
AUXSW_AUTO = 16, // change to auto flight mode
|
||||
AUXSW_AUTOTUNE = 17, // auto tune
|
||||
AUXSW_LAND = 18, // change to LAND flight mode
|
||||
|
@ -51,7 +51,6 @@ LIBRARIES += AP_Notify
|
||||
LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_BoardConfig
|
||||
LIBRARIES += AP_Frsky_Telem
|
||||
LIBRARIES += AC_Sprayer
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += AP_RPM
|
||||
LIBRARIES += AC_InputManager
|
||||
|
@ -189,11 +189,6 @@ bool Sub::init_arm_motors(bool arming_from_gcs)
|
||||
ahrs.set_correct_centrifugal(true);
|
||||
hal.util->set_soft_armed(true);
|
||||
|
||||
#if SPRAYER == ENABLED
|
||||
// turn off sprayer's test if on
|
||||
sprayer.test_pump(false);
|
||||
#endif
|
||||
|
||||
// enable output to motors
|
||||
enable_motor_output();
|
||||
|
||||
|
@ -234,7 +234,6 @@ void Sub::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
|
||||
case AUXSW_SUPERSIMPLE_MODE:
|
||||
case AUXSW_ACRO_TRAINER:
|
||||
case AUXSW_GRIPPER:
|
||||
case AUXSW_SPRAYER:
|
||||
case AUXSW_RETRACT_MOUNT:
|
||||
case AUXSW_MISSION_RESET:
|
||||
case AUXSW_ATTCON_FEEDFWD:
|
||||
@ -387,13 +386,6 @@ void Sub::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#if SPRAYER == ENABLED
|
||||
case AUXSW_SPRAYER:
|
||||
sprayer.enable(ch_flag == AUX_SWITCH_HIGH);
|
||||
// if we are disarmed the pilot must want to test the pump
|
||||
sprayer.test_pump((ch_flag == AUX_SWITCH_HIGH) && !motors.armed());
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AUXSW_AUTO:
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
|
@ -13,7 +13,6 @@ def build(bld):
|
||||
'AC_Fence',
|
||||
'AC_Avoidance',
|
||||
'AC_PID',
|
||||
'AC_Sprayer',
|
||||
'AC_WPNav',
|
||||
'AP_Camera',
|
||||
'AP_InertialNav',
|
||||
|
Loading…
Reference in New Issue
Block a user