2021-12-23 19:56:57 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
2012-03-09 22:51:28 -04:00
2021-12-23 19:56:57 -04:00
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# pragma once
2021-12-24 01:47:21 -04:00
# include <AP_HAL/AP_HAL_Boards.h>
# ifndef AP_OPTICALFLOW_ENABLED
# define AP_OPTICALFLOW_ENABLED 1
# endif
# ifndef HAL_MSP_OPTICALFLOW_ENABLED
# define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES))
# endif
2022-08-22 08:20:11 -03:00
# ifndef AP_OPTICALFLOW_SITL_ENABLED
# define AP_OPTICALFLOW_SITL_ENABLED AP_SIM_ENABLED
# endif
2021-12-24 01:47:21 -04:00
# if AP_OPTICALFLOW_ENABLED
2021-12-23 19:56:57 -04:00
/*
2022-01-19 20:20:48 -04:00
* AP_OpticalFlow . h - OpticalFlow Base Class for ArduPilot
2021-12-23 19:56:57 -04:00
*/
# include <AP_MSP/msp.h>
# include <AP_Math/AP_Math.h>
# include <GCS_MAVLink/GCS_MAVLink.h>
2022-01-19 23:21:06 -04:00
# include "AP_OpticalFlow_Calibrator.h"
2021-12-23 19:56:57 -04:00
class OpticalFlow_backend ;
2022-08-14 22:31:14 -03:00
class AP_OpticalFlow
2021-12-23 19:56:57 -04:00
{
friend class OpticalFlow_backend ;
public :
2022-08-14 22:31:14 -03:00
AP_OpticalFlow ( ) ;
2021-12-23 19:56:57 -04:00
2022-08-14 22:31:14 -03:00
CLASS_NO_COPY ( AP_OpticalFlow ) ;
2021-12-23 19:56:57 -04:00
// get singleton instance
2022-08-14 22:31:14 -03:00
static AP_OpticalFlow * get_singleton ( ) {
2021-12-23 19:56:57 -04:00
return _singleton ;
}
2022-08-14 22:31:14 -03:00
enum class Type {
2021-12-23 19:56:57 -04:00
NONE = 0 ,
PX4FLOW = 1 ,
PIXART = 2 ,
BEBOP = 3 ,
CXOF = 4 ,
MAVLINK = 5 ,
UAVCAN = 6 ,
MSP = 7 ,
UPFLOW = 8 ,
SITL = 10 ,
} ;
// init - initialise sensor
void init ( uint32_t log_bit ) ;
// enabled - returns true if optical flow is enabled
2022-08-14 22:31:14 -03:00
bool enabled ( ) const { return _type ! = Type : : NONE ; }
2021-12-23 19:56:57 -04:00
// healthy - return true if the sensor is healthy
bool healthy ( ) const { return backend ! = nullptr & & _flags . healthy ; }
// read latest values from sensor and fill in x,y and totals.
void update ( void ) ;
// handle optical flow mavlink messages
void handle_msg ( const mavlink_message_t & msg ) ;
# if HAL_MSP_OPTICALFLOW_ENABLED
// handle optical flow msp messages
void handle_msp ( const MSP : : msp_opflow_data_message_t & pkt ) ;
# endif
// quality - returns the surface quality as a measure from 0 ~ 255
uint8_t quality ( ) const { return _state . surface_quality ; }
// raw - returns the raw movement from the sensor
const Vector2f & flowRate ( ) const { return _state . flowRate ; }
// velocity - returns the velocity in m/s
const Vector2f & bodyRate ( ) const { return _state . bodyRate ; }
// last_update() - returns system time of last sensor update
uint32_t last_update ( ) const { return _last_update_ms ; }
2022-10-24 00:01:10 -03:00
// get_height_override() - returns the user-specified height of sensor above ground
float get_height_override ( ) const { return _height_override ; }
2021-12-23 19:56:57 -04:00
struct OpticalFlow_state {
uint8_t surface_quality ; // image quality (below TBD you can't trust the dx,dy values returned)
Vector2f flowRate ; // optical flow angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
Vector2f bodyRate ; // body inertial angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
} ;
// return a 3D vector defining the position offset of the sensors focal point in metres relative to the body frame origin
const Vector3f & get_pos_offset ( void ) const {
return _pos_offset ;
}
2022-01-19 23:21:06 -04:00
// start or stop calibration
void start_calibration ( ) ;
void stop_calibration ( ) ;
2021-12-23 19:56:57 -04:00
// parameter var info table
static const struct AP_Param : : GroupInfo var_info [ ] ;
private :
2022-08-14 22:31:14 -03:00
static AP_OpticalFlow * _singleton ;
2021-12-23 19:56:57 -04:00
OpticalFlow_backend * backend ;
struct AP_OpticalFlow_Flags {
uint8_t healthy : 1 ; // true if sensor is healthy
} _flags ;
// parameters
2022-08-14 22:31:14 -03:00
AP_Enum < Type > _type ; // user configurable sensor type
2021-12-23 19:56:57 -04:00
AP_Int16 _flowScalerX ; // X axis flow scale factor correction - parts per thousand
AP_Int16 _flowScalerY ; // Y axis flow scale factor correction - parts per thousand
AP_Int16 _yawAngle_cd ; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees
AP_Vector3f _pos_offset ; // position offset of the flow sensor in the body frame
AP_Int8 _address ; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow)
2022-10-24 00:01:10 -03:00
AP_Float _height_override ; // height of the sensor above the ground. Only used in rover
2021-12-23 19:56:57 -04:00
// method called by backend to update frontend state:
void update_state ( const OpticalFlow_state & state ) ;
// state filled in by backend
struct OpticalFlow_state _state ;
uint32_t _last_update_ms ; // millis() time of last update
void Log_Write_Optflow ( ) ;
uint32_t _log_bit = - 1 ; // bitmask bit which indicates if we should log. -1 means we always log
2022-01-19 23:21:06 -04:00
// calibrator
AP_OpticalFlow_Calibrator * _calibrator ;
2021-12-23 19:56:57 -04:00
} ;
namespace AP {
2022-08-14 22:31:14 -03:00
AP_OpticalFlow * opticalflow ( ) ;
2021-12-23 19:56:57 -04:00
}
2021-12-24 01:38:56 -04:00
# include "AP_OpticalFlow_Backend.h"
2021-12-24 01:47:21 -04:00
# endif // AP_OPTICALFLOW_ENABLED