AntennaTracker: implement HAL::Callbacks

Also removes includes for each board since they are not necessary
anymore.
This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-10-19 16:32:37 -02:00 committed by Andrew Tridgell
parent 06b2c966c1
commit b648715496
2 changed files with 6 additions and 26 deletions

View File

@ -127,19 +127,4 @@ Tracker::Tracker(void)
Tracker tracker; Tracker tracker;
/* AP_HAL_MAIN_CALLBACKS(&tracker);
compatibility with old pde style build
*/
void setup(void);
void loop(void);
void setup(void)
{
tracker.setup();
}
void loop(void)
{
tracker.loop();
}
AP_HAL_MAIN();

View File

@ -76,21 +76,16 @@
#include "Parameters.h" #include "Parameters.h"
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h> class Tracker : public AP_HAL::HAL::Callbacks {
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
class Tracker {
public: public:
friend class GCS_MAVLINK; friend class GCS_MAVLINK;
friend class Parameters; friend class Parameters;
Tracker(void); Tracker(void);
void setup();
void loop(); // HAL::Callbacks implementation.
void setup() override;
void loop() override;
private: private:
const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ; const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ;