mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Copter: change the default of zigzag wp delay to 0
This commit is contained in:
parent
32e628f267
commit
0ff28df2ba
@ -30,9 +30,9 @@ const AP_Param::GroupInfo ModeZigZag::var_info[] = {
|
|||||||
// @DisplayName: The delay for zigzag waypoint
|
// @DisplayName: The delay for zigzag waypoint
|
||||||
// @Description: Waiting time after reached the destination
|
// @Description: Waiting time after reached the destination
|
||||||
// @Units: s
|
// @Units: s
|
||||||
// @Range: 1 127
|
// @Range: 0 127
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("WP_DELAY", 3, ModeZigZag, _wp_delay, 1),
|
AP_GROUPINFO("WP_DELAY", 3, ModeZigZag, _wp_delay, 0),
|
||||||
|
|
||||||
// @Param: SIDE_DIST
|
// @Param: SIDE_DIST
|
||||||
// @DisplayName: Sideways distance in ZigZag auto
|
// @DisplayName: Sideways distance in ZigZag auto
|
||||||
@ -409,7 +409,7 @@ bool ModeZigZag::reached_destination()
|
|||||||
if (reach_wp_time_ms == 0) {
|
if (reach_wp_time_ms == 0) {
|
||||||
reach_wp_time_ms = now;
|
reach_wp_time_ms = now;
|
||||||
}
|
}
|
||||||
return ((now - reach_wp_time_ms) > (uint16_t)constrain_int16(_wp_delay, 1, 127) * 1000);
|
return ((now - reach_wp_time_ms) >= (uint16_t)constrain_int16(_wp_delay, 0, 127) * 1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculate next destination according to vector A-B and current position
|
// calculate next destination according to vector A-B and current position
|
||||||
|
Loading…
Reference in New Issue
Block a user