mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: correct payload_place flytolocation
This commit is contained in:
parent
09d8a33aaf
commit
17c12dab2a
@ -933,6 +933,7 @@ void Copter::ModeAuto::payload_place_run()
|
|||||||
|
|
||||||
switch (nav_payload_place.state) {
|
switch (nav_payload_place.state) {
|
||||||
case PayloadPlaceStateType_FlyToLocation:
|
case PayloadPlaceStateType_FlyToLocation:
|
||||||
|
return wp_run();
|
||||||
case PayloadPlaceStateType_Calibrating_Hover_Start:
|
case PayloadPlaceStateType_Calibrating_Hover_Start:
|
||||||
case PayloadPlaceStateType_Calibrating_Hover:
|
case PayloadPlaceStateType_Calibrating_Hover:
|
||||||
return payload_place_run_loiter();
|
return payload_place_run_loiter();
|
||||||
@ -1564,9 +1565,8 @@ bool Copter::ModeAuto::verify_payload_place()
|
|||||||
if (!copter.wp_nav->reached_wp_destination()) {
|
if (!copter.wp_nav->reached_wp_destination()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
// we're there; set loiter target
|
payload_place_start();
|
||||||
nav_payload_place.state = PayloadPlaceStateType_Calibrating_Hover_Start;
|
return false;
|
||||||
FALLTHROUGH;
|
|
||||||
case PayloadPlaceStateType_Calibrating_Hover_Start:
|
case PayloadPlaceStateType_Calibrating_Hover_Start:
|
||||||
// hover for 1 second to get an idea of what our hover
|
// hover for 1 second to get an idea of what our hover
|
||||||
// throttle looks like
|
// throttle looks like
|
||||||
|
Loading…
Reference in New Issue
Block a user