Copter: add ZIGZAG_WP_DELAY parameter

This commit is contained in:
Tatsuya Yamaguchi 2020-04-02 17:25:39 +09:00 committed by Randy Mackay
parent 923237ffd3
commit 63002111eb
4 changed files with 21 additions and 7 deletions

View File

@ -963,14 +963,24 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),
#endif
#if MODE_ZIGZAG_ENABLED == ENABLED && SPRAYER_ENABLED == ENABLED
#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.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("ZIGZAG_AUTO_PUMP", 38, ParametersG2, zigzag_auto_pump_enabled, ZIGZAG_AUTO_PUMP_ENABLED),
#endif
#endif // SPRAYER_ENABLED == ENABLED
// @Param: ZIGZ_WP_DELAY
// @DisplayName: The delay for zigzag waypoint
// @Description: Waiting time after reached the destination
// @Units: s
// @Range: 1 127
// @User: Advanced
AP_GROUPINFO("ZIGZ_WP_DELAY", 39, ParametersG2, zigzag_wp_delay, ZIGZAG_WP_DELAY),
#endif // MODE_ZIGZAG_ENABLED == ENABLED
AP_GROUPEND

View File

@ -611,10 +611,13 @@ public:
AC_Autorotation arot;
#endif
#if MODE_ZIGZAG_ENABLED == ENABLED && SPRAYER_ENABLED == ENABLED
#if MODE_ZIGZAG_ENABLED == ENABLED
#if SPRAYER_ENABLED == ENABLED
// auto pump enable/disable
AP_Int8 zigzag_auto_pump_enabled;
#endif
AP_Int8 zigzag_wp_delay;
#endif
};

View File

@ -364,10 +364,11 @@
// ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B
#ifndef MODE_ZIGZAG_ENABLED
# define MODE_ZIGZAG_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#if MODE_ZIGZAG_ENABLED == ENABLED && HAL_SPRAYER_ENABLED
# define ZIGZAG_WP_DELAY 1
#if HAL_SPRAYER_ENABLED
# define ZIGZAG_AUTO_PUMP_ENABLED DISABLED
#endif
#endif
//////////////////////////////////////////////////////////////////////////////

View File

@ -313,12 +313,12 @@ bool ModeZigZag::reached_destination()
return false;
}
// wait at least one second
// wait at time which is set in zigzag_wp_delay
uint32_t now = AP_HAL::millis();
if (reach_wp_time_ms == 0) {
reach_wp_time_ms = now;
}
return ((now - reach_wp_time_ms) > 1000);
return ((now - reach_wp_time_ms) > (uint16_t)constrain_int16(g2.zigzag_wp_delay, 1, 127) * 1000);
}
// calculate next destination according to vector A-B and current position