2016-11-18 05:56:05 -04:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2014-07-11 23:27:28 -03:00
# include "OpticalFlow.h"
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"
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.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)
# define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::PIXART
# elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
# define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::BEBOP
# else
# define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::NONE
# endif
# endif
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo OpticalFlow : : var_info [ ] = {
2019-04-04 01:32:46 -03:00
// @Param: _TYPE
// @DisplayName: Optical flow sensor type
// @Description: Optical flow sensor type
2020-08-04 17:42:52 -03:00
// @Values: 0:None, 1:PX4Flow, 2:Pixart, 3:Bebop, 4:CXOF, 5:MAVLink, 6:UAVCAN, 7:MSP
2014-07-11 23:27:28 -03:00
// @User: Standard
2019-04-04 01:32:46 -03:00
// @RebootRequired: True
AP_GROUPINFO ( " _TYPE " , 0 , OpticalFlow , _type , ( int8_t ) OPTICAL_FLOW_TYPE_DEFAULT ) ,
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.
// @Range: -200 +200
2014-11-02 18:22:20 -04:00
// @Increment: 1
// @User: Standard
2014-11-11 05:04:14 -04:00
AP_GROUPINFO ( " _FXSCALER " , 1 , OpticalFlow , _flowScalerX , 0 ) ,
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.
// @Range: -200 +200
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " _FYSCALER " , 2 , 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
2015-04-06 05:04:24 -03:00
// @Range: -18000 +18000
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " _ORIENT_YAW " , 3 , OpticalFlow , _yawAngle_cd , 0 ) ,
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
AP_GROUPINFO ( " _POS " , 4 , OpticalFlow , _pos_offset , 0.0f ) ,
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
2017-08-21 23:23:18 -03:00
AP_GROUPINFO ( " _ADDR " , 5 , OpticalFlow , _address , 0 ) ,
2019-04-04 01:32:46 -03:00
2014-07-11 23:27:28 -03:00
AP_GROUPEND
} ;
// default constructor
2018-09-02 03:54:04 -03:00
OpticalFlow : : 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
2018-09-02 09:27:29 -03:00
void 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
if ( ( _type = = ( int8_t ) OpticalFlowType : : NONE ) | | ( backend ! = nullptr ) ) {
2017-08-22 00:17:06 -03:00
return ;
}
2019-04-04 01:32:46 -03:00
switch ( ( OpticalFlowType ) _type . get ( ) ) {
case OpticalFlowType : : NONE :
break ;
case OpticalFlowType : : PX4FLOW :
2016-11-25 23:21:28 -04:00
backend = AP_OpticalFlow_PX4Flow : : detect ( * this ) ;
2019-04-04 01:32:46 -03:00
break ;
case OpticalFlowType : : PIXART :
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
}
2019-04-04 01:32:46 -03:00
break ;
case OpticalFlowType : : BEBOP :
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
backend = new AP_OpticalFlow_Onboard ( * this ) ;
# endif
break ;
case OpticalFlowType : : CXOF :
backend = AP_OpticalFlow_CXOF : : detect ( * this ) ;
break ;
case OpticalFlowType : : MAVLINK :
backend = AP_OpticalFlow_MAV : : detect ( * this ) ;
break ;
2018-10-19 22:51:51 -03:00
case OpticalFlowType : : UAVCAN :
2020-05-31 09:36:07 -03:00
# if HAL_ENABLE_LIBUAVCAN_DRIVERS
2018-10-19 22:51:51 -03:00
backend = new AP_OpticalFlow_HereFlow ( * this ) ;
# endif
break ;
2020-08-04 17:42:52 -03:00
case OpticalFlowType : : 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 ;
2019-04-04 01:32:46 -03:00
case OpticalFlowType : : SITL :
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
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 ( ) ;
}
}
void OpticalFlow : : update ( void )
{
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 ) ;
2015-01-02 04:30:32 -04:00
}
2019-04-30 07:22:49 -03:00
void 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
2020-09-07 19:28:22 -03:00
void 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
2018-09-02 09:27:29 -03:00
void OpticalFlow : : update_state ( const OpticalFlow_state & state )
{
_state = state ;
_last_update_ms = AP_HAL : : millis ( ) ;
// write to log and send to EKF if new data has arrived
AP : : ahrs_navekf ( ) . writeOptFlowMeas ( quality ( ) ,
_state . flowRate ,
_state . bodyRate ,
_last_update_ms ,
get_pos_offset ( ) ) ;
Log_Write_Optflow ( ) ;
}
void OpticalFlow : : Log_Write_Optflow ( )
{
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
}
2018-09-02 03:32:12 -03:00
// singleton instance
OpticalFlow * OpticalFlow : : _singleton ;
namespace AP {
OpticalFlow * opticalflow ( )
{
return OpticalFlow : : get_singleton ( ) ;
}
}