Copter: guided velocity contoller inits accel and jerk

In practice this has no functional impact because the guided_pos_control_start initialises these values (using AC_WPNav) and it is not currently possible for a user to get to the velocity controller without having first used the guided position controller
This commit is contained in:
Randy Mackay 2017-04-27 13:21:31 +09:00
parent e0de1517c1
commit a342b73604
1 changed files with 6 additions and 1 deletions

View File

@ -107,7 +107,12 @@ void Copter::guided_vel_control_start()
// set guided_mode to velocity controller // set guided_mode to velocity controller
guided_mode = Guided_Velocity; guided_mode = Guided_Velocity;
// initialize vertical speeds and leash lengths // initialise horizontal speed, acceleration and jerk
pos_control->set_speed_xy(wp_nav->get_speed_xy());
pos_control->set_accel_xy(wp_nav->get_wp_acceleration());
pos_control->set_jerk_xy_to_default();
// initialize vertical speeds and 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);