AC_AttitudeControl: removed empty constructors

This commit is contained in:
divyateja04 2021-10-27 11:02:33 +05:30 committed by Peter Barker
parent 7daa276769
commit 7f0bf89003
4 changed files with 2 additions and 17 deletions

View File

@ -19,12 +19,6 @@
*/ */
#include "AC_AttitudeControl_TS.h" #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) void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch)
{ {
// If exclude_pitch: relax roll and yaw rate controller outputs only, // If exclude_pitch: relax roll and yaw rate controller outputs only,

View File

@ -5,11 +5,10 @@
#include "AC_AttitudeControl_Multi.h" #include "AC_AttitudeControl_Multi.h"
class AC_AttitudeControl_TS : public AC_AttitudeControl_Multi class AC_AttitudeControl_TS : public AC_AttitudeControl_Multi
{ {
public: 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 // empty destructor to suppress compiler warning
virtual ~AC_AttitudeControl_TS() {} virtual ~AC_AttitudeControl_TS() {}

View File

@ -1,12 +1,5 @@
#include "AC_PosControl_Sub.h" #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. /// 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 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. /// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z.

View File

@ -6,8 +6,7 @@
class AC_PosControl_Sub : public AC_PosControl { class AC_PosControl_Sub : public AC_PosControl {
public: public:
AC_PosControl_Sub(AP_AHRS_View & ahrs, const AP_InertialNav& inav, using AC_PosControl::AC_PosControl;
const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt);
/// set_alt_max - sets maximum altitude above the ekf origin in cm /// 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 /// only enforced when set_pos_target_z_from_climb_rate_cm is used