2016-11-19 02:21:25 -04:00
|
|
|
#pragma once
|
|
|
|
|
2021-12-23 20:05:30 -04:00
|
|
|
#include "AP_OpticalFlow.h"
|
2016-11-19 02:21:25 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
#include <SITL/SITL.h>
|
|
|
|
|
|
|
|
class AP_OpticalFlow_SITL : public OpticalFlow_backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
/// constructor
|
|
|
|
AP_OpticalFlow_SITL(OpticalFlow &_frontend);
|
|
|
|
|
|
|
|
// init - initialise the sensor
|
2019-02-21 19:11:28 -04:00
|
|
|
void init() override;
|
2016-11-19 02:21:25 -04:00
|
|
|
|
|
|
|
// update - read latest values from sensor and fill in x,y and totals.
|
2019-02-21 19:11:28 -04:00
|
|
|
void update(void) override;
|
2016-11-19 02:21:25 -04:00
|
|
|
|
|
|
|
private:
|
2021-07-30 07:15:10 -03:00
|
|
|
SITL::SIM *_sitl;
|
2016-11-19 02:21:25 -04:00
|
|
|
uint32_t last_flow_ms;
|
|
|
|
|
|
|
|
uint8_t next_optflow_index;
|
|
|
|
uint8_t optflow_delay;
|
|
|
|
OpticalFlow::OpticalFlow_state optflow_data[20];
|
|
|
|
};
|
|
|
|
#endif // CONFIG_HAL_BOARD
|