2016-11-18 05:56:05 -04:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2021-12-23 20:05:30 -04:00
# include "AP_OpticalFlow.h"
2021-12-24 01:47:21 -04:00
# if AP_OPTICALFLOW_ENABLED
2015-11-24 05:34:08 -04:00
# include "AP_OpticalFlow_Onboard.h"
2016-11-25 23:21:28 -04:00
# include "AP_OpticalFlow_SITL.h"
# include "AP_OpticalFlow_Pixart.h"
# include "AP_OpticalFlow_PX4Flow.h"
2018-11-23 03:45:53 -04:00
# include "AP_OpticalFlow_CXOF.h"
2019-03-27 04:18:35 -03:00
# include "AP_OpticalFlow_MAV.h"
2018-10-19 22:51:51 -03:00
# include "AP_OpticalFlow_HereFlow.h"
2020-08-04 17:42:52 -03:00
# include "AP_OpticalFlow_MSP.h"
2021-03-12 07:56:34 -04:00
# include "AP_OpticalFlow_UPFLOW.h"
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.h>
2022-01-19 23:21:06 -04:00
# include <GCS_MAVLink/GCS.h>
2014-07-11 23:27:28 -03:00
2015-01-02 04:30:32 -04:00
extern const AP_HAL : : HAL & hal ;
2019-04-04 01:32:46 -03:00
# ifndef OPTICAL_FLOW_TYPE_DEFAULT
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 || defined(HAL_HAVE_PIXARTFLOW_SPI)
2022-08-14 22:31:14 -03:00
# define OPTICAL_FLOW_TYPE_DEFAULT Type::PIXART
2019-04-04 01:32:46 -03:00
# elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
2022-08-14 22:31:14 -03:00
# define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP
2019-04-04 01:32:46 -03:00
# else
2022-08-14 22:31:14 -03:00
# define OPTICAL_FLOW_TYPE_DEFAULT Type::NONE
2019-04-04 01:32:46 -03:00
# endif
# endif
2022-08-14 22:31:14 -03:00
const AP_Param : : GroupInfo AP_OpticalFlow : : var_info [ ] = {
2019-04-04 01:32:46 -03:00
// @Param: _TYPE
// @DisplayName: Optical flow sensor type
// @Description: Optical flow sensor type
2021-12-13 21:32:24 -04:00
// @Values: 0:None, 1:PX4Flow, 2:Pixart, 3:Bebop, 4:CXOF, 5:MAVLink, 6:DroneCAN, 7:MSP, 8:UPFLOW
2014-07-11 23:27:28 -03:00
// @User: Standard
2019-04-04 01:32:46 -03:00
// @RebootRequired: True
2022-08-14 22:31:14 -03:00
AP_GROUPINFO_FLAGS ( " _TYPE " , 0 , AP_OpticalFlow , _type , ( float ) OPTICAL_FLOW_TYPE_DEFAULT , AP_PARAM_FLAG_ENABLE ) ,
2014-07-11 23:27:28 -03:00
2015-07-05 23:09:11 -03:00
// @Param: _FXSCALER
2014-11-11 05:04:14 -04:00
// @DisplayName: X axis optical flow scale factor correction
// @Description: This sets the parts per thousand scale factor correction applied to the flow sensor X axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the X axis optical flow reading by 0.1%. Negative values reduce the scale factor.
2023-11-10 04:19:44 -04:00
// @Range: -800 +800
2014-11-02 18:22:20 -04:00
// @Increment: 1
// @User: Standard
2022-08-14 22:31:14 -03:00
AP_GROUPINFO ( " _FXSCALER " , 1 , AP_OpticalFlow , _flowScalerX , 0 ) ,
2014-11-11 05:04:14 -04:00
2015-07-05 23:09:11 -03:00
// @Param: _FYSCALER
2014-11-11 05:04:14 -04:00
// @DisplayName: Y axis optical flow scale factor correction
// @Description: This sets the parts per thousand scale factor correction applied to the flow sensor Y axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the Y axis optical flow reading by 0.1%. Negative values reduce the scale factor.
2023-11-10 04:19:44 -04:00
// @Range: -800 +800
2014-11-11 05:04:14 -04:00
// @Increment: 1
// @User: Standard
2022-08-14 22:31:14 -03:00
AP_GROUPINFO ( " _FYSCALER " , 2 , AP_OpticalFlow , _flowScalerY , 0 ) ,
2014-11-02 20:47:09 -04:00
2015-07-05 23:09:11 -03:00
// @Param: _ORIENT_YAW
2015-04-06 05:04:24 -03:00
// @DisplayName: Flow sensor yaw alignment
// @Description: Specifies the number of centi-degrees that the flow sensor is yawed relative to the vehicle. A sensor with its X-axis pointing to the right of the vehicle X axis has a positive yaw angle.
2020-02-03 00:39:40 -04:00
// @Units: cdeg
2021-05-20 10:08:46 -03:00
// @Range: -17999 +18000
// @Increment: 10
2015-04-06 05:04:24 -03:00
// @User: Standard
2022-08-14 22:31:14 -03:00
AP_GROUPINFO ( " _ORIENT_YAW " , 3 , AP_OpticalFlow , _yawAngle_cd , 0 ) ,
2015-04-06 05:04:24 -03:00
2016-10-07 19:56:00 -03:00
// @Param: _POS_X
// @DisplayName: X position offset
2016-10-18 19:38:36 -03:00
// @Description: X position of the optical flow sensor focal point in body frame. Positive X is forward of the origin.
2016-10-07 19:56:00 -03:00
// @Units: m
2020-01-30 00:31:41 -04:00
// @Range: -5 5
// @Increment: 0.01
2016-10-07 19:56:00 -03:00
// @User: Advanced
// @Param: _POS_Y
// @DisplayName: Y position offset
2016-10-18 19:38:36 -03:00
// @Description: Y position of the optical flow sensor focal point in body frame. Positive Y is to the right of the origin.
2016-10-07 19:56:00 -03:00
// @Units: m
2020-01-30 00:31:41 -04:00
// @Range: -5 5
// @Increment: 0.01
2016-10-07 19:56:00 -03:00
// @User: Advanced
// @Param: _POS_Z
// @DisplayName: Z position offset
2016-10-18 19:38:36 -03:00
// @Description: Z position of the optical flow sensor focal point in body frame. Positive Z is down from the origin.
2016-10-07 19:56:00 -03:00
// @Units: m
2020-01-30 00:31:41 -04:00
// @Range: -5 5
// @Increment: 0.01
2016-10-07 19:56:00 -03:00
// @User: Advanced
2022-08-14 22:31:14 -03:00
AP_GROUPINFO ( " _POS " , 4 , AP_OpticalFlow , _pos_offset , 0.0f ) ,
2016-10-07 19:56:00 -03:00
2017-08-21 23:23:18 -03:00
// @Param: _ADDR
// @DisplayName: Address on the bus
// @Description: This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus.
2017-02-10 20:26:26 -04:00
// @Range: 0 127
2016-11-25 23:21:28 -04:00
// @User: Advanced
2022-08-14 22:31:14 -03:00
AP_GROUPINFO ( " _ADDR " , 5 , AP_OpticalFlow , _address , 0 ) ,
2019-04-04 01:32:46 -03:00
2022-10-24 00:01:10 -03:00
// @Param: _HGT_OVR
// @DisplayName: Height override of sensor above ground
// @Description: This is used in rover vehicles, where the sensor is a fixed height above the ground
// @Units: m
// @Range: 0 2
// @Increment: 0.01
// @User: Advanced
AP_GROUPINFO_FRAME ( " _HGT_OVR " , 6 , AP_OpticalFlow , _height_override , 0.0f , AP_PARAM_FRAME_ROVER ) ,
2014-07-11 23:27:28 -03:00
AP_GROUPEND
} ;
// default constructor
2022-08-14 22:31:14 -03:00
AP_OpticalFlow : : AP_OpticalFlow ( )
2014-07-11 23:27:28 -03:00
{
2018-09-02 03:32:12 -03:00
_singleton = this ;
2014-07-11 23:27:28 -03:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2016-05-12 16:03:06 -03:00
}
2015-01-02 04:30:32 -04:00
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : init ( uint32_t log_bit )
2015-01-02 04:30:32 -04:00
{
2018-09-02 09:27:29 -03:00
_log_bit = log_bit ;
2019-04-04 01:32:46 -03:00
// return immediately if not enabled or backend already created
2022-08-14 22:31:14 -03:00
if ( ( _type = = Type : : NONE ) | | ( backend ! = nullptr ) ) {
2017-08-22 00:17:06 -03:00
return ;
}
2022-08-14 22:31:14 -03:00
switch ( ( Type ) _type ) {
case Type : : NONE :
2019-04-04 01:32:46 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : PX4FLOW :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_PX4FLOW_ENABLED
2016-11-25 23:21:28 -04:00
backend = AP_OpticalFlow_PX4Flow : : detect ( * this ) ;
2021-12-24 04:17:50 -04:00
# endif
2019-04-04 01:32:46 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : PIXART :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_PIXART_ENABLED
2018-02-14 01:41:37 -04:00
backend = AP_OpticalFlow_Pixart : : detect ( " pixartflow " , * this ) ;
2019-03-27 01:49:42 -03:00
if ( backend = = nullptr ) {
2019-04-04 01:32:46 -03:00
backend = AP_OpticalFlow_Pixart : : detect ( " pixartPC15 " , * this ) ;
2019-03-27 04:18:35 -03:00
}
2021-12-24 04:17:50 -04:00
# endif
2019-04-04 01:32:46 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : BEBOP :
2019-04-04 01:32:46 -03:00
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
backend = new AP_OpticalFlow_Onboard ( * this ) ;
# endif
break ;
2022-08-14 22:31:14 -03:00
case Type : : CXOF :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_CXOF_ENABLED
2019-04-04 01:32:46 -03:00
backend = AP_OpticalFlow_CXOF : : detect ( * this ) ;
2021-12-24 04:17:50 -04:00
# endif
2019-04-04 01:32:46 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : MAVLINK :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_MAV_ENABLED
2019-04-04 01:32:46 -03:00
backend = AP_OpticalFlow_MAV : : detect ( * this ) ;
2021-12-24 04:17:50 -04:00
# endif
2019-04-04 01:32:46 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : UAVCAN :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_HEREFLOW_ENABLED
2018-10-19 22:51:51 -03:00
backend = new AP_OpticalFlow_HereFlow ( * this ) ;
# endif
break ;
2022-08-14 22:31:14 -03:00
case Type : : MSP :
2020-09-01 04:54:50 -03:00
# if HAL_MSP_OPTICALFLOW_ENABLED
2020-08-04 17:42:52 -03:00
backend = AP_OpticalFlow_MSP : : detect ( * this ) ;
2020-09-01 04:54:50 -03:00
# endif
2020-08-31 01:22:04 -03:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : UPFLOW :
2021-12-24 04:17:50 -04:00
# if AP_OPTICALFLOW_UPFLOW_ENABLED
2021-03-12 07:56:34 -04:00
backend = AP_OpticalFlow_UPFLOW : : detect ( * this ) ;
2021-12-24 04:17:50 -04:00
# endif
2021-03-12 07:56:34 -04:00
break ;
2022-08-14 22:31:14 -03:00
case Type : : SITL :
2022-08-22 08:20:11 -03:00
# if AP_OPTICALFLOW_SITL_ENABLED
2019-04-04 01:32:46 -03:00
backend = new AP_OpticalFlow_SITL ( * this ) ;
# endif
break ;
2016-05-12 16:03:06 -03:00
}
2016-10-30 02:24:21 -03:00
if ( backend ! = nullptr ) {
2015-01-02 04:30:32 -04:00
backend - > init ( ) ;
}
}
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : update ( void )
2015-01-02 04:30:32 -04:00
{
2018-09-02 09:27:29 -03:00
// exit immediately if not enabled
if ( ! enabled ( ) ) {
return ;
}
2016-10-30 02:24:21 -03:00
if ( backend ! = nullptr ) {
2015-01-02 04:30:32 -04:00
backend - > update ( ) ;
}
2018-09-02 09:27:29 -03:00
2015-01-02 04:30:32 -04:00
// only healthy if the data is less than 0.5s old
2015-11-19 23:13:34 -04:00
_flags . healthy = ( AP_HAL : : millis ( ) - _last_update_ms < 500 ) ;
2022-01-19 23:21:06 -04:00
2023-07-12 03:23:33 -03:00
# if AP_OPTICALFLOW_CALIBRATOR_ENABLED
2022-01-19 23:21:06 -04:00
// update calibrator and save resulting scaling
if ( _calibrator ! = nullptr ) {
if ( _calibrator - > update ( ) ) {
// apply new calibration values
const Vector2f new_scaling = _calibrator - > get_scalars ( ) ;
2022-01-28 23:37:35 -04:00
const float flow_scalerx_as_multiplier = ( 1.0 + ( _flowScalerX * 0.001 ) ) * new_scaling . x ;
const float flow_scalery_as_multiplier = ( 1.0 + ( _flowScalerY * 0.001 ) ) * new_scaling . y ;
2022-01-19 23:21:06 -04:00
_flowScalerX . set_and_save_ifchanged ( ( flow_scalerx_as_multiplier - 1.0 ) * 1000.0 ) ;
_flowScalerY . set_and_save_ifchanged ( ( flow_scalery_as_multiplier - 1.0 ) * 1000.0 ) ;
_flowScalerX . notify ( ) ;
_flowScalerY . notify ( ) ;
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " FlowCal: FLOW_FXSCALER=%d, FLOW_FYSCALER=%d " , ( int ) _flowScalerX , ( int ) _flowScalerY ) ;
}
}
2023-07-12 03:23:33 -03:00
# endif
2015-01-02 04:30:32 -04:00
}
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : handle_msg ( const mavlink_message_t & msg )
2019-03-27 04:18:35 -03:00
{
// exit immediately if not enabled
if ( ! enabled ( ) ) {
return ;
}
if ( backend ! = nullptr ) {
backend - > handle_msg ( msg ) ;
}
}
2020-09-01 04:54:50 -03:00
# if HAL_MSP_OPTICALFLOW_ENABLED
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : handle_msp ( const MSP : : msp_opflow_data_message_t & pkt )
2020-08-04 17:42:52 -03:00
{
// exit immediately if not enabled
if ( ! enabled ( ) ) {
return ;
}
if ( backend ! = nullptr ) {
backend - > handle_msp ( pkt ) ;
}
}
2020-09-01 04:54:50 -03:00
# endif //HAL_MSP_OPTICALFLOW_ENABLED
2020-08-04 17:42:52 -03:00
2023-07-12 03:23:33 -03:00
# if AP_OPTICALFLOW_CALIBRATOR_ENABLED
2022-01-19 23:21:06 -04:00
// start calibration
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : start_calibration ( )
2022-01-19 23:21:06 -04:00
{
if ( _calibrator = = nullptr ) {
_calibrator = new AP_OpticalFlow_Calibrator ( ) ;
if ( _calibrator = = nullptr ) {
GCS_SEND_TEXT ( MAV_SEVERITY_CRITICAL , " FlowCal: failed to start " ) ;
return ;
}
}
if ( _calibrator ! = nullptr ) {
_calibrator - > start ( ) ;
}
}
// stop calibration
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : stop_calibration ( )
2022-01-19 23:21:06 -04:00
{
if ( _calibrator ! = nullptr ) {
_calibrator - > stop ( ) ;
}
}
2023-07-12 03:23:33 -03:00
# endif
2022-01-19 23:21:06 -04:00
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : update_state ( const OpticalFlow_state & state )
2018-09-02 09:27:29 -03:00
{
_state = state ;
_last_update_ms = AP_HAL : : millis ( ) ;
// write to log and send to EKF if new data has arrived
2021-07-20 09:16:31 -03:00
AP : : ahrs ( ) . writeOptFlowMeas ( quality ( ) ,
_state . flowRate ,
_state . bodyRate ,
_last_update_ms ,
2022-10-24 00:01:10 -03:00
get_pos_offset ( ) ,
get_height_override ( ) ) ;
2023-07-12 03:22:54 -03:00
# if HAL_LOGGING_ENABLED
2018-09-02 09:27:29 -03:00
Log_Write_Optflow ( ) ;
2023-07-12 03:22:54 -03:00
# endif
2018-09-02 09:27:29 -03:00
}
2023-07-12 03:22:54 -03:00
# if HAL_LOGGING_ENABLED
2022-08-14 22:31:14 -03:00
void AP_OpticalFlow : : Log_Write_Optflow ( )
2018-09-02 09:27:29 -03:00
{
2019-02-11 04:34:06 -04:00
AP_Logger * logger = AP_Logger : : get_singleton ( ) ;
if ( logger = = nullptr ) {
2018-09-02 09:27:29 -03:00
return ;
}
if ( _log_bit ! = ( uint32_t ) - 1 & &
2019-02-11 04:34:06 -04:00
! logger - > should_log ( _log_bit ) ) {
2018-09-02 09:27:29 -03:00
return ;
}
struct log_Optflow pkt = {
LOG_PACKET_HEADER_INIT ( LOG_OPTFLOW_MSG ) ,
time_us : AP_HAL : : micros64 ( ) ,
surface_quality : _state . surface_quality ,
flow_x : _state . flowRate . x ,
flow_y : _state . flowRate . y ,
body_x : _state . bodyRate . x ,
body_y : _state . bodyRate . y
} ;
2019-02-11 04:34:06 -04:00
logger - > WriteBlock ( & pkt , sizeof ( pkt ) ) ;
2018-09-02 09:27:29 -03:00
}
2023-07-12 03:22:54 -03:00
# endif // HAL_LOGGING_ENABLED
2018-09-02 09:27:29 -03:00
2018-09-02 03:32:12 -03:00
// singleton instance
2022-08-14 22:31:14 -03:00
AP_OpticalFlow * AP_OpticalFlow : : _singleton ;
2018-09-02 03:32:12 -03:00
namespace AP {
2022-08-14 22:31:14 -03:00
AP_OpticalFlow * opticalflow ( )
2018-09-02 03:32:12 -03:00
{
2022-08-14 22:31:14 -03:00
return AP_OpticalFlow : : get_singleton ( ) ;
2018-09-02 03:32:12 -03:00
}
}
2021-12-24 01:47:21 -04:00
# endif // AP_OPTICALFLOW_ENABLED