mirror of https://github.com/ArduPilot/ardupilot
Copter: PosHold supports offsets
This commit is contained in:
parent
5ca7daf915
commit
1c59ec8b94
|
@ -377,7 +377,7 @@ void ModePosHold::run()
|
|||
pitch_mode = RPMode::BRAKE_TO_LOITER;
|
||||
brake.to_loiter_timer = POSHOLD_BRAKE_TO_LOITER_TIMER;
|
||||
// init loiter controller
|
||||
loiter_nav->init_target(inertial_nav.get_position_xy_cm());
|
||||
loiter_nav->init_target(inertial_nav.get_position_xy_cm() - pos_control->get_pos_offset_cm().xy().tofloat());
|
||||
// set delay to start of wind compensation estimate updates
|
||||
wind_comp_start_timer = POSHOLD_WIND_COMP_START_TIMER;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue