From 7f0bf8900368163773a995c58fb6da5c892c8443 Mon Sep 17 00:00:00 2001 From: divyateja04 Date: Wed, 27 Oct 2021 11:02:33 +0530 Subject: [PATCH] AC_AttitudeControl: removed empty constructors --- libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp | 6 ------ libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h | 3 +-- libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp | 7 ------- libraries/AC_AttitudeControl/AC_PosControl_Sub.h | 3 +-- 4 files changed, 2 insertions(+), 17 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp index 9e74e0e0da..3596d18b5d 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp @@ -19,12 +19,6 @@ */ #include "AC_AttitudeControl_TS.h" - -AC_AttitudeControl_TS::AC_AttitudeControl_TS(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : - AC_AttitudeControl_Multi(ahrs, aparm, motors, dt) -{ -} - void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch) { // If exclude_pitch: relax roll and yaw rate controller outputs only, diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h index f300131e6d..b0d7c0720c 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h @@ -5,11 +5,10 @@ #include "AC_AttitudeControl_Multi.h" - class AC_AttitudeControl_TS : public AC_AttitudeControl_Multi { public: - AC_AttitudeControl_TS(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); + using AC_AttitudeControl_Multi::AC_AttitudeControl_Multi; // empty destructor to suppress compiler warning virtual ~AC_AttitudeControl_TS() {} diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp index bdae565b2e..fcca412188 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp @@ -1,12 +1,5 @@ #include "AC_PosControl_Sub.h" -AC_PosControl_Sub::AC_PosControl_Sub(AP_AHRS_View& ahrs, const AP_InertialNav& inav, - const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt) : - AC_PosControl(ahrs, inav, motors, attitude_control, dt), - _alt_max(0.0f), - _alt_min(0.0f) -{} - /// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration. /// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. /// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z. diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h index 5f36c0f6ee..3d9c4f5f59 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h @@ -6,8 +6,7 @@ class AC_PosControl_Sub : public AC_PosControl { public: - AC_PosControl_Sub(AP_AHRS_View & ahrs, const AP_InertialNav& inav, - const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt); + using AC_PosControl::AC_PosControl; /// set_alt_max - sets maximum altitude above the ekf origin in cm /// only enforced when set_pos_target_z_from_climb_rate_cm is used