mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Copter: rename zigzag_auto_pump to zigzag_sprayer
This commit is contained in:
parent
63002111eb
commit
60fb275501
@ -965,12 +965,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
|
||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
// @Param: ZIGZAG_AUTO_PUMP
|
||||
// @DisplayName: Auto pump in ZigZag
|
||||
// @Description: Enable the auto pump in ZigZag mode. SERVOx_FUNCTION = 22 (SprayerPump) and SPRAY_ENABLE = 1 also must be set. This makes the pump on while moving to destination A or B. The pump will stop if the vehicle reaches destination or the flight mode is changed from ZigZag to other.
|
||||
// @Param: ZIGZ_SPRAYER
|
||||
// @DisplayName: Auto sprayer in ZigZag
|
||||
// @Description: Enable the auto sprayer in ZigZag mode. SPRAY_ENABLE = 1 and SERVOx_FUNCTION = 22(SprayerPump) / 23(SprayerSpinner) also must be set. This makes the sprayer on while moving to destination A or B. The sprayer will stop if the vehicle reaches destination or the flight mode is changed from ZigZag to other.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ZIGZAG_AUTO_PUMP", 38, ParametersG2, zigzag_auto_pump_enabled, ZIGZAG_AUTO_PUMP_ENABLED),
|
||||
AP_GROUPINFO("ZIGZ_SPRAYER", 38, ParametersG2, zigzag_spray_enabled, ZIGZAG_SPRAY_ENABLED),
|
||||
#endif // SPRAYER_ENABLED == ENABLED
|
||||
|
||||
// @Param: ZIGZ_WP_DELAY
|
||||
|
@ -614,7 +614,7 @@ public:
|
||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
// auto pump enable/disable
|
||||
AP_Int8 zigzag_auto_pump_enabled;
|
||||
AP_Int8 zigzag_spray_enabled;
|
||||
#endif
|
||||
AP_Int8 zigzag_wp_delay;
|
||||
#endif
|
||||
|
@ -366,7 +366,7 @@
|
||||
# define MODE_ZIGZAG_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
# define ZIGZAG_WP_DELAY 1
|
||||
#if HAL_SPRAYER_ENABLED
|
||||
# define ZIGZAG_AUTO_PUMP_ENABLED DISABLED
|
||||
# define ZIGZAG_SPRAY_ENABLED DISABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -1418,6 +1418,7 @@ private:
|
||||
void manual_control();
|
||||
bool reached_destination();
|
||||
bool calculate_next_dest(Destination ab_dest, bool use_wpnav_alt, Vector3f& next_dest, bool& terrain_alt) const;
|
||||
void spray(bool b);
|
||||
|
||||
Vector2f dest_A; // in NEU frame in cm relative to ekf origin
|
||||
Vector2f dest_B; // in NEU frame in cm relative to ekf origin
|
||||
|
@ -44,12 +44,8 @@ bool ModeZigZag::init(bool ignore_checks)
|
||||
// perform cleanup required when leaving zigzag mode
|
||||
void ModeZigZag::exit()
|
||||
{
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
// The pump will stop if the flight mode is changed from ZigZag to other
|
||||
if (g2.zigzag_auto_pump_enabled) {
|
||||
copter.sprayer.run(false);
|
||||
}
|
||||
#endif
|
||||
// The sprayer will stop if the flight mode is changed from ZigZag to other
|
||||
spray(false);
|
||||
}
|
||||
|
||||
// run the zigzag controller
|
||||
@ -107,6 +103,10 @@ void ModeZigZag::save_or_move_to_destination(Destination ab_dest)
|
||||
// if both A and B have been stored advance state
|
||||
if (!dest_A.is_zero() && !dest_B.is_zero() && is_positive((dest_B - dest_A).length_squared())) {
|
||||
stage = MANUAL_REGAIN;
|
||||
spray(false);
|
||||
} else {
|
||||
// if only A or B have been stored, spray on
|
||||
spray(true);
|
||||
}
|
||||
break;
|
||||
|
||||
@ -119,12 +119,8 @@ void ModeZigZag::save_or_move_to_destination(Destination ab_dest)
|
||||
wp_nav->wp_and_spline_init();
|
||||
if (wp_nav->set_wp_destination(next_dest, terr_alt)) {
|
||||
stage = AUTO;
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
// spray on while moving to A or B
|
||||
if (g2.zigzag_auto_pump_enabled) {
|
||||
copter.sprayer.run(true);
|
||||
}
|
||||
#endif
|
||||
spray(true);
|
||||
reach_wp_time_ms = 0;
|
||||
if (ab_dest == Destination::A) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: moving to A");
|
||||
@ -142,12 +138,7 @@ void ModeZigZag::return_to_manual_control(bool maintain_target)
|
||||
{
|
||||
if (stage == AUTO) {
|
||||
stage = MANUAL_REGAIN;
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
// spray off
|
||||
if (g2.zigzag_auto_pump_enabled) {
|
||||
copter.sprayer.run(false);
|
||||
}
|
||||
#endif
|
||||
spray(false);
|
||||
loiter_nav->clear_pilot_desired_acceleration();
|
||||
if (maintain_target) {
|
||||
const Vector3f& wp_dest = wp_nav->get_wp_destination();
|
||||
@ -377,4 +368,14 @@ bool ModeZigZag::calculate_next_dest(Destination ab_dest, bool use_wpnav_alt, Ve
|
||||
return true;
|
||||
}
|
||||
|
||||
// spray on / off
|
||||
void ModeZigZag::spray(bool b)
|
||||
{
|
||||
#if SPRAYER_ENABLED == ENABLED
|
||||
if (g2.zigzag_spray_enabled) {
|
||||
copter.sprayer.run(b);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // MODE_ZIGZAG_ENABLED == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user