Copter: init pos_control z-axis after setting speed and accel

This commit is contained in:
Randy Mackay 2014-04-30 16:29:32 +09:00
parent cad1441739
commit a3036fc443
5 changed files with 16 additions and 14 deletions

View File

@ -7,13 +7,13 @@
// althold_init - initialise althold controller
static bool althold_init(bool ignore_checks)
{
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialize vertical speeds and leash lengths
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}

View File

@ -192,13 +192,13 @@ static bool autotune_init(bool ignore_checks)
return false;
}
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialize vertical speeds and leash lengths
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}

View File

@ -101,13 +101,13 @@ static bool hybrid_init(bool ignore_checks)
return false;
}
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialize vertical speeds and leash lengths
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialise lean angles to current attitude
hybrid.pilot_roll = 0;
hybrid.pilot_pitch = 0;

View File

@ -16,12 +16,13 @@ static bool land_init(bool ignore_checks)
wp_nav.set_loiter_target(stopping_point);
}
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialize vertical speeds and leash lengths
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
pos_control.set_accel_z(wp_nav.get_accel_z());
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}

View File

@ -9,13 +9,14 @@ static bool ofloiter_init(bool ignore_checks)
{
#if OPTFLOW == ENABLED
if (g.optflow_enabled || ignore_checks) {
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
// initialize vertical speed and acceleration
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}else{
return false;