AP_OpticalFlow: allow use of OpticalFlow on SimOnHardWare

This commit is contained in:
Peter Barker 2022-08-22 21:20:11 +10:00 committed by Andrew Tridgell
parent 6926466d88
commit 46aebe3020
5 changed files with 18 additions and 25 deletions

View File

@ -160,7 +160,7 @@ void AP_OpticalFlow::init(uint32_t log_bit)
#endif
break;
case Type::SITL:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if AP_OPTICALFLOW_SITL_ENABLED
backend = new AP_OpticalFlow_SITL(*this);
#endif
break;

View File

@ -24,6 +24,10 @@
#define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES))
#endif
#ifndef AP_OPTICALFLOW_SITL_ENABLED
#define AP_OPTICALFLOW_SITL_ENABLED AP_SIM_ENABLED
#endif
#if AP_OPTICALFLOW_ENABLED
/*

View File

@ -32,7 +32,7 @@ public:
CLASS_NO_COPY(OpticalFlow_backend);
// init - initialise sensor
virtual void init() = 0;
virtual void init() {}
// read latest values from sensor and fill in x,y and totals.
virtual void update() = 0;

View File

@ -17,26 +17,17 @@
* AP_OpticalFlow_SITL.cpp - SITL emulation of optical flow sensor.
*/
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_OpticalFlow_SITL.h"
extern const AP_HAL::HAL& hal;
#if AP_OPTICALFLOW_SITL_ENABLED
AP_OpticalFlow_SITL::AP_OpticalFlow_SITL(AP_OpticalFlow &_frontend) :
OpticalFlow_backend(_frontend),
_sitl(AP::sitl())
{
}
void AP_OpticalFlow_SITL::init(void)
{
}
#include <AP_HAL/AP_HAL.h>
#include <SITL/SITL.h>
void AP_OpticalFlow_SITL::update(void)
{
auto *_sitl = AP::sitl();
if (!_sitl->flow_enable) {
return;
}
@ -128,4 +119,4 @@ void AP_OpticalFlow_SITL::update(void)
_update_frontend(state);
}
#endif // CONFIG_HAL_BOARD
#endif // AP_OPTICALFLOW_SITL_ENABLED

View File

@ -1,27 +1,25 @@
#pragma once
#include "AP_OpticalFlow.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#if AP_OPTICALFLOW_SITL_ENABLED
class AP_OpticalFlow_SITL : public OpticalFlow_backend
{
public:
/// constructor
AP_OpticalFlow_SITL(AP_OpticalFlow &_frontend);
// init - initialise the sensor
void init() override;
using OpticalFlow_backend::OpticalFlow_backend;
// update - read latest values from sensor and fill in x,y and totals.
void update(void) override;
private:
SITL::SIM *_sitl;
uint32_t last_flow_ms;
uint8_t next_optflow_index;
uint8_t optflow_delay;
AP_OpticalFlow::OpticalFlow_state optflow_data[20];
};
#endif // CONFIG_HAL_BOARD
#endif // AP_OPTICALFLOW_SITL_ENABLED