AP_OpticalFlow: use new scheduler API

This commit is contained in:
Andrew Tridgell 2013-09-28 16:29:43 +10:00
parent 03036c632d
commit f53afaa5ac
4 changed files with 10 additions and 17 deletions

View File

@ -23,13 +23,6 @@
#define FORTYFIVE_DEGREES 0.78539816f
// pointer to the last instantiated optical flow sensor. Will be turned into
// a table if we ever add support for more than one sensor
AP_OpticalFlow* AP_OpticalFlow::_sensor = NULL;
// number of times we have been called by 1khz timer process.
// We use this to throttle read down to 20hz
uint8_t AP_OpticalFlow::_num_calls;
bool AP_OpticalFlow::init()
{
_orientation = ROTATION_NONE;
@ -47,7 +40,7 @@ void AP_OpticalFlow::set_orientation(enum Rotation rotation)
// parent method called at 1khz by periodic process
// this is slowed down to 20hz and each instance's update function is called
// (only one instance is supported at the moment)
void AP_OpticalFlow::read(uint32_t now)
void AP_OpticalFlow::read(void)
{
_num_calls++;
@ -55,13 +48,13 @@ void AP_OpticalFlow::read(uint32_t now)
_num_calls = 0;
// call to update all attached sensors
if( _sensor != NULL ) {
_sensor->update(now);
_sensor->update();
}
}
};
// read value from the sensor. Should be overridden by derived class
void AP_OpticalFlow::update(uint32_t now){ }
void AP_OpticalFlow::update(void){ }
// reads a value from the sensor (will be sensor specific)
uint8_t AP_OpticalFlow::read_register(uint8_t address){ return 0; }

View File

@ -58,10 +58,10 @@ public:
virtual void set_field_of_view(const float fov) { field_of_view = fov; update_conversion_factors(); };
// called by timer process to read sensor data from all attached sensors
static void read(uint32_t now);
void read();
// read latest values from sensor and fill in x,y and totals.
virtual void update(uint32_t now);
virtual void update();
// updates internal lon and lat with estimation based on optical flow
virtual void update_position(float roll, float pitch, float sin_yaw, float cos_yaw, float altitude);
@ -86,7 +86,7 @@ public:
protected:
// pointer to the last instantiated optical flow sensor. Will be turned
// into a table if we ever add support for more than one sensor
static AP_OpticalFlow * _sensor;
AP_OpticalFlow * _sensor;
enum Rotation _orientation;
// multiply this number by altitude and pixel change to get horizontal
// move (in same units as altitude)
@ -102,7 +102,7 @@ protected:
private:
// number of times we have been called by 1khz timer process.
// We use this to throttle read down to 20hz
static uint8_t _num_calls;
uint8_t _num_calls;
};
#include "AP_OpticalFlow_ADNS3080.h"

View File

@ -102,7 +102,7 @@ finish:
// if device is working register the global static read function to
// be called at 1khz
if( retvalue ) {
hal.scheduler->register_timer_process( AP_OpticalFlow_ADNS3080::read );
hal.scheduler->register_timer_process(reinterpret_cast<AP_HAL::TimedProc>(&AP_OpticalFlow_ADNS3080::read), this);
}
// resume timer
@ -194,7 +194,7 @@ AP_OpticalFlow_ADNS3080::reset()
// read latest values from sensor and fill in x,y and totals
void
AP_OpticalFlow_ADNS3080::update(uint32_t now)
AP_OpticalFlow_ADNS3080::update(void)
{
uint8_t motion_reg;
surface_quality = read_register(ADNS3080_SQUAL);

View File

@ -94,7 +94,7 @@ public:
// read latest values from sensor and fill in x,y and totals,
// returns true on successful read
void update(uint32_t now);
void update(void);
// ADNS3080 specific features