Copter: remove reset of alt target in manual throttle mode

the target was being set to zero only for logging purposes
This commit is contained in:
Randy Mackay 2018-11-21 08:54:43 +09:00
parent 6816262e3d
commit 655fe660ed
4 changed files with 8 additions and 10 deletions

View File

@ -86,6 +86,12 @@ void Copter::Log_Write_Control_Tuning()
terr_alt = DataFlash.quiet_nan();
}
#endif
float des_alt_m = 0.0f;
int16_t target_climb_rate_cms = 0;
if (!flightmode->has_manual_throttle()) {
des_alt_m = pos_control->get_alt_target() / 100.0f;
target_climb_rate_cms = pos_control->get_vel_target_z();
}
float _target_rangefinder_alt;
if (target_rangefinder_alt_used) {
@ -100,13 +106,13 @@ void Copter::Log_Write_Control_Tuning()
angle_boost : attitude_control->angle_boost(),
throttle_out : motors->get_throttle(),
throttle_hover : motors->get_throttle_hover(),
desired_alt : pos_control->get_alt_target() / 100.0f,
desired_alt : des_alt_m,
inav_alt : inertial_nav.get_altitude() / 100.0f,
baro_alt : baro_alt,
desired_rangefinder_alt : _target_rangefinder_alt,
rangefinder_alt : rangefinder_state.alt_cm,
terr_alt : terr_alt,
target_climb_rate : (int16_t)pos_control->get_vel_target_z(),
target_climb_rate : target_climb_rate_cms,
climb_rate : climb_rate
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));

View File

@ -15,8 +15,6 @@ bool Copter::ModeAcro::init(bool ignore_checks)
(get_pilot_desired_throttle(channel_throttle->get_control_in(), copter.g2.acro_thr_mid) > copter.get_non_takeoff_throttle())) {
return false;
}
// set target altitude to zero for reporting
pos_control->set_alt_target(0);
return true;
}

View File

@ -12,8 +12,6 @@ bool Copter::ModeStabilize::init(bool ignore_checks)
(get_pilot_desired_throttle(channel_throttle->get_control_in()) > get_non_takeoff_throttle())) {
return false;
}
// set target altitude to zero for reporting
pos_control->set_alt_target(0);
return true;
}

View File

@ -8,10 +8,6 @@
// stabilize_init - initialise stabilize controller
bool Copter::ModeStabilize_Heli::init(bool ignore_checks)
{
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control->set_alt_target(0);
// set stab collective true to use stabilize scaled collective pitch range
copter.input_manager.set_use_stab_col(true);