@ -33,7 +33,7 @@
@@ -33,7 +33,7 @@
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
* @ file accelerometer_calibration . c
* @ file accelerometer_calibration . cpp
*
* Implementation of accelerometer calibration .
*
@ -113,8 +113,6 @@
@@ -113,8 +113,6 @@
# include <sys/prctl.h>
# include <math.h>
# include <string.h>
# include <drivers/drv_hrt.h>
# include <uORB/topics/sensor_combined.h>
# include <drivers/drv_accel.h>
@ -123,6 +121,12 @@
@@ -123,6 +121,12 @@
# include <systemlib/err.h>
# include <mavlink/mavlink_log.h>
/* oddly, ERROR is not defined for c++ */
# ifdef ERROR
# undef ERROR
# endif
static const int ERROR = - 1 ;
int do_accel_calibration_measurements ( int mavlink_fd , float accel_offs [ 3 ] , float accel_scale [ 3 ] ) ;
int detect_orientation ( int mavlink_fd , int sub_sensor_combined ) ;
int read_accelerometer_avg ( int sensor_combined_sub , float accel_avg [ 3 ] , int samples_num ) ;
@ -229,7 +233,10 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
@@ -229,7 +233,10 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
sprintf ( str , " meas started: %s " , orientation_strs [ orient ] ) ;
mavlink_log_info ( mavlink_fd , str ) ;
read_accelerometer_avg ( sensor_combined_sub , & ( accel_ref [ orient ] [ 0 ] ) , samples_num ) ;
str_ptr = sprintf ( str , " meas result for %s: [ %.2f %.2f %.2f ] " , orientation_strs [ orient ] , accel_ref [ orient ] [ 0 ] , accel_ref [ orient ] [ 1 ] , accel_ref [ orient ] [ 2 ] ) ;
str_ptr = sprintf ( str , " meas result for %s: [ %.2f %.2f %.2f ] " , orientation_strs [ orient ] ,
( double ) accel_ref [ orient ] [ 0 ] ,
( double ) accel_ref [ orient ] [ 1 ] ,
( double ) accel_ref [ orient ] [ 2 ] ) ;
mavlink_log_info ( mavlink_fd , str ) ;
data_collected [ orient ] = true ;
tune_neutral ( ) ;
@ -274,7 +281,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
@@ -274,7 +281,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
float accel_err_thr = 5.0f ;
/* still time required in us */
int64_t still_time = 2000000 ;
struct pollfd fds [ 1 ] = { { . fd = sub_sensor_combined , . events = POLLIN } } ;
struct pollfd fds [ 1 ] ;
fds [ 0 ] . fd = sub_sensor_combined ;
fds [ 0 ] . events = POLLIN ;
hrt_abstime t_start = hrt_absolute_time ( ) ;
/* set timeout to 30s */
@ -342,29 +351,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
@@ -342,29 +351,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
}
}
if ( fabs ( accel_ema [ 0 ] - CONSTANTS_ONE_G ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] - CONSTANTS_ONE_G ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] ) < accel_err_thr )
return 0 ; // [ g, 0, 0 ]
if ( fabs ( accel_ema [ 0 ] + CONSTANTS_ONE_G ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] + CONSTANTS_ONE_G ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] ) < accel_err_thr )
return 1 ; // [ -g, 0, 0 ]
if ( fabs ( accel_ema [ 0 ] ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] - CONSTANTS_ONE_G ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] - CONSTANTS_ONE_G ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] ) < accel_err_thr )
return 2 ; // [ 0, g, 0 ]
if ( fabs ( accel_ema [ 0 ] ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] + CONSTANTS_ONE_G ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] + CONSTANTS_ONE_G ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] ) < accel_err_thr )
return 3 ; // [ 0, -g, 0 ]
if ( fabs ( accel_ema [ 0 ] ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] - CONSTANTS_ONE_G ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] - CONSTANTS_ONE_G ) < accel_err_thr )
return 4 ; // [ 0, 0, g ]
if ( fabs ( accel_ema [ 0 ] ) < accel_err_thr & &
fabs ( accel_ema [ 1 ] ) < accel_err_thr & &
fabs ( accel_ema [ 2 ] + CONSTANTS_ONE_G ) < accel_err_thr )
if ( fabsf ( accel_ema [ 0 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 1 ] ) < accel_err_thr & &
fabsf ( accel_ema [ 2 ] + CONSTANTS_ONE_G ) < accel_err_thr )
return 5 ; // [ 0, 0, -g ]
mavlink_log_info ( mavlink_fd , " ERROR: invalid orientation " ) ;
@ -376,7 +385,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
@@ -376,7 +385,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
* Read specified number of accelerometer samples , calculate average and dispersion .
*/
int read_accelerometer_avg ( int sensor_combined_sub , float accel_avg [ 3 ] , int samples_num ) {
struct pollfd fds [ 1 ] = { { . fd = sensor_combined_sub , . events = POLLIN } } ;
struct pollfd fds [ 1 ] ;
fds [ 0 ] . fd = sensor_combined_sub ;
fds [ 0 ] . events = POLLIN ;
int count = 0 ;
float accel_sum [ 3 ] = { 0.0f , 0.0f , 0.0f } ;