AC_PosControl_Sub: move pids to be local

This commit is contained in:
Randy Mackay 2017-11-21 11:46:27 +09:00
parent c70d3e0ab8
commit 9c00eb3d5f
2 changed files with 3 additions and 7 deletions

View File

@ -1,10 +1,8 @@
#include "AC_PosControl_Sub.h"
AC_PosControl_Sub::AC_PosControl_Sub(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control,
AC_P& p_pos_z, AC_P& p_vel_z, AC_PID& pid_accel_z,
AC_P& p_pos_xy) :
AC_PosControl(ahrs, inav, motors, attitude_control, p_pos_z, p_vel_z, pid_accel_z, p_pos_xy),
const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
AC_PosControl(ahrs, inav, motors, attitude_control),
_alt_max(0.0f),
_alt_min(0.0f)
{}

View File

@ -5,9 +5,7 @@
class AC_PosControl_Sub : public AC_PosControl {
public:
AC_PosControl_Sub(const AP_AHRS_View & ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control,
AC_P& p_pos_z, AC_P& p_vel_z, AC_PID& pid_accel_z,
AC_P& p_pos_xy);
const AP_Motors& motors, AC_AttitudeControl& attitude_control);
/// set_alt_max - sets maximum altitude above the ekf origin in cm
/// only enforced when set_alt_target_from_climb_rate is used