mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
Copter: set pos controller speeds before circle init
This ensures stopping point is calculated correctly
This commit is contained in:
parent
1cb297580f
commit
0af9d502d9
@ -9,12 +9,16 @@ static bool circle_init(bool ignore_checks)
|
|||||||
{
|
{
|
||||||
if ((GPS_ok() && inertial_nav.position_ok()) || ignore_checks) {
|
if ((GPS_ok() && inertial_nav.position_ok()) || ignore_checks) {
|
||||||
circle_pilot_yaw_override = false;
|
circle_pilot_yaw_override = false;
|
||||||
circle_nav.init();
|
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize speeds and accelerations
|
||||||
|
pos_control.set_speed_xy(wp_nav.get_speed_xy());
|
||||||
|
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
|
||||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
|
// initialise circle controller including setting the circle center based on vehicle speed
|
||||||
|
circle_nav.init();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}else{
|
}else{
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user