mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AC_PID: replace header guard with pragma once
This commit is contained in:
parent
498693d0b8
commit
f637a29ab6
@ -1,11 +1,9 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
|
|
||||||
/// @file AC_HELI_PID.h
|
/// @file AC_HELI_PID.h
|
||||||
/// @brief Helicopter Specific Rate PID algorithm, with EEPROM-backed storage of constants.
|
/// @brief Helicopter Specific Rate PID algorithm, with EEPROM-backed storage of constants.
|
||||||
|
|
||||||
#ifndef __AC_HELI_PID_H__
|
|
||||||
#define __AC_HELI_PID_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -45,5 +43,3 @@ private:
|
|||||||
float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
|
float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AC_HELI_PID_H__
|
|
||||||
|
@ -1,11 +1,9 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
|
|
||||||
/// @file AC_PD.h
|
/// @file AC_PD.h
|
||||||
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
||||||
|
|
||||||
#ifndef __AC_P_H__
|
|
||||||
#define __AC_P_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -67,5 +65,3 @@ public:
|
|||||||
private:
|
private:
|
||||||
AP_Float _kp;
|
AP_Float _kp;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AC_P_H__
|
|
||||||
|
@ -1,11 +1,9 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
|
|
||||||
/// @file AC_PID.h
|
/// @file AC_PID.h
|
||||||
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
||||||
|
|
||||||
#ifndef __AC_PID_H__
|
|
||||||
#define __AC_PID_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -106,5 +104,3 @@ protected:
|
|||||||
|
|
||||||
DataFlash_Class::PID_Info _pid_info;
|
DataFlash_Class::PID_Info _pid_info;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AC_PID_H__
|
|
||||||
|
@ -1,11 +1,9 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
|
|
||||||
/// @file AC_PI_2D.h
|
/// @file AC_PI_2D.h
|
||||||
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
||||||
|
|
||||||
#ifndef __AC_PI_2D_H__
|
|
||||||
#define __AC_PI_2D_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -94,5 +92,3 @@ protected:
|
|||||||
Vector2f _input; // last input for derivative
|
Vector2f _input; // last input for derivative
|
||||||
float _filt_alpha; // input filter alpha
|
float _filt_alpha; // input filter alpha
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AC_PI_2D_H__
|
|
||||||
|
Loading…
Reference in New Issue
Block a user