ardupilot/libraries/APO/AP_Autopilot.h

124 lines
2.4 KiB
C
Raw Normal View History

2011-09-28 21:51:12 -03:00
/*
* AP_Autopilot.h
*
* Created on: Apr 30, 2011
* Author: jgoppert
*/
#ifndef AP_AUTOPILOT_H_
#define AP_AUTOPILOT_H_
#include "../AP_Common/AP_Loop.h"
/**
2011-10-03 07:40:24 -03:00
* ArduPilotOne namespace to protect variables
2011-09-28 21:51:12 -03:00
* from overlap with avr and libraries etc.
* ArduPilotOne does not use any global
* variables.
*/
2011-11-29 14:59:44 -04:00
2011-09-28 21:51:12 -03:00
namespace apo {
2011-11-29 14:59:44 -04:00
// enumerations
2011-09-28 21:51:12 -03:00
// forward declarations
2011-10-26 15:59:40 -03:00
class AP_Navigator;
class AP_Guide;
class AP_Controller;
2011-12-07 17:31:56 -04:00
class AP_Board;
2011-09-28 21:51:12 -03:00
/**
* This class encapsulates the entire autopilot system
* The constructor takes guide, navigator, and controller
* as well as the hardware abstraction layer.
*
* It inherits from loop to manage
2011-10-03 07:40:24 -03:00
* the sub-loops and sets the overall
2011-09-28 21:51:12 -03:00
* frequency for the autopilot.
*
*/
class AP_Autopilot: public Loop {
public:
2011-10-26 13:31:11 -03:00
/**
* Default constructor
*/
AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
2011-12-07 17:31:56 -04:00
AP_Controller * controller, AP_Board * board,
2011-10-26 13:31:11 -03:00
float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate);
/**
* Accessors
*/
AP_Navigator * getNavigator() {
return _navigator;
}
AP_Guide * getGuide() {
return _guide;
}
AP_Controller * getController() {
return _controller;
}
2011-12-07 17:31:56 -04:00
AP_Board * getBoard() {
return _board;
2011-10-26 13:31:11 -03:00
}
/**
* Loop Monitoring
*/
uint32_t callbackCalls;
2011-09-28 21:51:12 -03:00
private:
2011-10-26 13:31:11 -03:00
/**
* Loop Callbacks (fastest)
* - inertial navigation
* @param data A void pointer used to pass the apo class
* so that the apo public interface may be accessed.
*/
static void callback(void * data);
/**
* Loop 0 Callbacks
* - control
* - compass reading
* @see callback
*/
static void callback0(void * data);
/**
* Loop 1 Callbacks
* - gps sensor fusion
* - compass sensor fusion
* @see callback
*/
static void callback1(void * data);
/**
* Loop 2 Callbacks
* - slow messages
* @see callback
*/
static void callback2(void * data);
/**
* Loop 3 Callbacks
* - super slow messages
* - log writing
* @see callback
*/
static void callback3(void * data);
/**
* Components
*/
AP_Navigator * _navigator;
AP_Guide * _guide;
AP_Controller * _controller;
2011-12-07 17:31:56 -04:00
AP_Board * _board;
2011-09-28 21:51:12 -03:00
};
} // namespace apo
#endif /* AP_AUTOPILOT_H_ */
2011-10-26 15:59:40 -03:00
// vim:ts=4:sw=4:expandtab