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"
2014-07-11 23:27:28 -03:00
2015-01-02 04:30:32 -04:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo OpticalFlow : : var_info [ ] = {
2015-07-05 23:09:11 -03:00
// @Param: _ENABLE
2014-07-11 23:27:28 -03:00
// @DisplayName: Optical flow enable/disable
// @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
AP_GROUPINFO ( " _ENABLE " , 0 , OpticalFlow , _enabled , 0 ) ,
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.
// @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
// @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
// @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
// @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 ) ,
2016-11-25 23:21:28 -04:00
2014-07-11 23:27:28 -03:00
AP_GROUPEND
} ;
// default constructor
2016-05-12 16:03:06 -03:00
OpticalFlow : : OpticalFlow ( AP_AHRS_NavEKF & ahrs )
2016-11-22 06:27:08 -04:00
: _ahrs ( ahrs ) ,
_last_update_ms ( 0 )
2014-07-11 23:27:28 -03:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
2015-01-02 04:30:32 -04:00
memset ( & _state , 0 , sizeof ( _state ) ) ;
// healthy flag will be overwritten on update
2014-07-11 23:27:28 -03:00
_flags . healthy = false ;
2016-05-12 16:03:06 -03:00
}
2015-01-02 04:30:32 -04:00
void OpticalFlow : : init ( void )
{
2017-08-22 00:17:06 -03:00
// return immediately if not enabled
if ( ! _enabled ) {
return ;
}
2016-05-12 16:03:06 -03:00
if ( ! backend ) {
2018-01-10 15:03:43 -04:00
# if AP_FEATURE_BOARD_DETECT
2018-01-18 03:18:23 -04:00
if ( AP_BoardConfig : : get_board_type ( ) = = AP_BoardConfig : : PX4_BOARD_PIXHAWK | |
2018-02-14 01:41:37 -04:00
AP_BoardConfig : : get_board_type ( ) = = AP_BoardConfig : : PX4_BOARD_PIXHAWK2 | |
2018-01-18 03:18:23 -04:00
AP_BoardConfig : : get_board_type ( ) = = AP_BoardConfig : : PX4_BOARD_PCNC1 ) {
2016-11-18 05:56:05 -04:00
// possibly have pixhart on external SPI
2018-02-14 01:41:37 -04:00
backend = AP_OpticalFlow_Pixart : : detect ( " pixartflow " , * this ) ;
}
if ( AP_BoardConfig : : get_board_type ( ) = = AP_BoardConfig : : PX4_BOARD_SP01 ) {
backend = AP_OpticalFlow_Pixart : : detect ( " pixartPC15 " , * this ) ;
2016-11-18 05:56:05 -04:00
}
if ( backend = = nullptr ) {
2016-11-25 23:21:28 -04:00
backend = AP_OpticalFlow_PX4Flow : : detect ( * this ) ;
2016-11-18 05:56:05 -04:00
}
2016-05-12 16:03:06 -03:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
2016-11-19 02:21:25 -04:00
backend = new AP_OpticalFlow_SITL ( * this ) ;
2018-06-21 20:40:22 -03:00
# elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
2016-11-19 03:18:50 -04:00
backend = new AP_OpticalFlow_Onboard ( * this ) ;
2016-11-21 13:04:20 -04:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
2016-11-25 23:21:28 -04:00
backend = AP_OpticalFlow_PX4Flow : : detect ( * this ) ;
2018-01-05 03:16:12 -04:00
# elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
2018-02-14 01:41:37 -04:00
backend = AP_OpticalFlow_Pixart : : detect ( " pixartflow " , * this ) ;
2016-05-12 16:03:06 -03:00
# endif
}
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 )
{
2016-10-30 02:24:21 -03:00
if ( backend ! = nullptr ) {
2015-01-02 04:30:32 -04:00
backend - > update ( ) ;
}
// 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
}