mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
APM_Control: changed to AP_Vehicle.h
This commit is contained in:
parent
15a4582ed7
commit
fbe4be94cf
@ -5,12 +5,12 @@
|
|||||||
|
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_SpdHgtControl.h>
|
#include <AP_Vehicle.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
class AP_PitchController {
|
class AP_PitchController {
|
||||||
public:
|
public:
|
||||||
AP_PitchController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) :
|
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||||
aparm(parms),
|
aparm(parms),
|
||||||
_ahrs(ahrs)
|
_ahrs(ahrs)
|
||||||
{
|
{
|
||||||
@ -26,7 +26,7 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_SpdHgtControl::AircraftParameters &aparm;
|
const AP_Vehicle::FixedWing &aparm;
|
||||||
AP_Float _tau;
|
AP_Float _tau;
|
||||||
AP_Float _K_P;
|
AP_Float _K_P;
|
||||||
AP_Float _K_I;
|
AP_Float _K_I;
|
||||||
|
@ -5,12 +5,12 @@
|
|||||||
|
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_SpdHgtControl.h>
|
#include <AP_Vehicle.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
class AP_RollController {
|
class AP_RollController {
|
||||||
public:
|
public:
|
||||||
AP_RollController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) :
|
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||||
aparm(parms),
|
aparm(parms),
|
||||||
_ahrs(ahrs)
|
_ahrs(ahrs)
|
||||||
{
|
{
|
||||||
@ -25,7 +25,7 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_SpdHgtControl::AircraftParameters &aparm;
|
const AP_Vehicle::FixedWing &aparm;
|
||||||
AP_Float _tau;
|
AP_Float _tau;
|
||||||
AP_Float _K_P;
|
AP_Float _K_P;
|
||||||
AP_Float _K_I;
|
AP_Float _K_I;
|
||||||
|
@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_SpdHgtControl.h>
|
#include <AP_Vehicle.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
class AP_SteerController {
|
class AP_SteerController {
|
||||||
|
@ -5,12 +5,12 @@
|
|||||||
|
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_SpdHgtControl.h>
|
#include <AP_Vehicle.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
class AP_YawController {
|
class AP_YawController {
|
||||||
public:
|
public:
|
||||||
AP_YawController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) :
|
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||||
aparm(parms),
|
aparm(parms),
|
||||||
_ahrs(ahrs)
|
_ahrs(ahrs)
|
||||||
{
|
{
|
||||||
@ -24,7 +24,7 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_SpdHgtControl::AircraftParameters &aparm;
|
const AP_Vehicle::FixedWing &aparm;
|
||||||
AP_Float _K_A;
|
AP_Float _K_A;
|
||||||
AP_Float _K_I;
|
AP_Float _K_I;
|
||||||
AP_Float _K_D;
|
AP_Float _K_D;
|
||||||
|
Loading…
Reference in New Issue
Block a user