2014-07-11 23:28:34 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
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 .
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/>.
*/
/*
* AP_OpticalFlow_PX4 . cpp - ardupilot library for PX4Flow sensor
*
*/
2014-10-15 03:51:05 -03:00
# include <AP_HAL.h>
2015-01-02 04:30:32 -04:00
# include "OpticalFlow.h"
2014-10-15 03:51:05 -03:00
2014-07-11 23:28:34 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
# include <sys/types.h>
# include <sys/stat.h>
# include <fcntl.h>
# include <unistd.h>
# include <drivers/drv_px4flow.h>
2014-10-15 02:25:55 -03:00
# include <uORB/topics/optical_flow.h>
2014-07-11 23:28:34 -03:00
extern const AP_HAL : : HAL & hal ;
2015-01-02 04:30:32 -04:00
AP_OpticalFlow_PX4 : : AP_OpticalFlow_PX4 ( OpticalFlow & _frontend ) :
OpticalFlow_backend ( _frontend )
{ }
2014-07-11 23:28:34 -03:00
void AP_OpticalFlow_PX4 : : init ( void )
{
2015-02-13 04:21:31 -04:00
_fd = open ( PX4FLOW0_DEVICE_PATH , O_RDONLY ) ;
2014-07-11 23:28:34 -03:00
// check for failure to open device
2014-12-31 20:02:43 -04:00
if ( _fd = = - 1 ) {
2014-07-11 23:28:34 -03:00
return ;
}
2014-12-06 03:14:43 -04:00
// change to 10Hz update
if ( ioctl ( _fd , SENSORIOCSPOLLRATE , 10 ) ! = 0 ) {
hal . console - > printf ( " Unable to set flow rate to 10Hz \n " ) ;
}
2014-07-11 23:28:34 -03:00
}
// update - read latest values from sensor and fill in x,y and totals.
void AP_OpticalFlow_PX4 : : update ( void )
{
2015-01-02 04:30:32 -04:00
// return immediately if not initialised
if ( _fd = = - 1 ) {
2014-10-15 04:27:19 -03:00
return ;
}
2014-10-15 02:25:55 -03:00
struct optical_flow_s report ;
2015-01-02 04:30:32 -04:00
while ( : : read ( _fd , & report , sizeof ( optical_flow_s ) ) = = sizeof ( optical_flow_s ) & &
report . timestamp ! = _last_timestamp ) {
struct OpticalFlow : : OpticalFlow_state state ;
state . device_id = report . sensor_id ;
state . surface_quality = report . quality ;
2014-10-31 20:23:24 -03:00
if ( report . integration_timespan > 0 ) {
2015-04-06 05:04:24 -03:00
float yawAngleRad = _yawAngleRad ( ) ;
float cosYaw = cosf ( yawAngleRad ) ;
float sinYaw = sinf ( yawAngleRad ) ;
2015-01-02 04:30:32 -04:00
const Vector2f flowScaler = _flowScaler ( ) ;
float flowScaleFactorX = 1.0f + 0.001f * flowScaler . x ;
float flowScaleFactorY = 1.0f + 0.001f * flowScaler . y ;
2014-11-07 07:59:02 -04:00
float integralToRate = 1e6 f / float ( report . integration_timespan ) ;
2015-04-06 05:04:24 -03:00
// rotate sensor measurements from sensor to body frame through sensor yaw angle
state . flowRate . x = flowScaleFactorX * integralToRate * ( cosYaw * float ( report . pixel_flow_x_integral ) - sinYaw * float ( report . pixel_flow_y_integral ) ) ; // rad/sec measured optically about the X body axis
state . flowRate . y = flowScaleFactorY * integralToRate * ( sinYaw * float ( report . pixel_flow_x_integral ) + cosYaw * float ( report . pixel_flow_y_integral ) ) ; // rad/sec measured optically about the Y body axis
state . bodyRate . x = integralToRate * ( cosYaw * float ( report . gyro_x_rate_integral ) - sinYaw * float ( report . gyro_y_rate_integral ) ) ; // rad/sec measured inertially about the X body axis
state . bodyRate . y = integralToRate * ( sinYaw * float ( report . gyro_x_rate_integral ) + cosYaw * float ( report . gyro_y_rate_integral ) ) ; // rad/sec measured inertially about the Y body axis
2014-10-31 20:23:24 -03:00
} else {
2015-01-02 04:30:32 -04:00
state . flowRate . zero ( ) ;
state . bodyRate . zero ( ) ;
2014-10-31 20:23:24 -03:00
}
2014-07-11 23:28:34 -03:00
_last_timestamp = report . timestamp ;
2015-01-02 04:30:32 -04:00
_update_frontend ( state ) ;
2014-07-11 23:28:34 -03:00
}
}
# endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4