SITL: push noise level to 2.0 for DCM testing

This commit is contained in:
Andrew Tridgell 2012-03-02 18:32:25 +11:00
parent 506b91a587
commit d2a969ee95

View File

@ -9,7 +9,7 @@
#include <stdlib.h> #include <stdlib.h>
#include <math.h> #include <math.h>
static const float vibration_level = 0.1; static const float vibration_level = 2.0;
// order zgyro, xgyro, ygyro, temp, xacc, yacc, zacc, aspd // order zgyro, xgyro, ygyro, temp, xacc, yacc, zacc, aspd
static const float noise_scale[8] = { 150, 150, 150, 0, 400, 400, 400, 0 }; static const float noise_scale[8] = { 150, 150, 150, 0, 400, 400, 400, 0 };
static const float noise_offset[8]= { 0, 0, 0, 0, 0, 0, 0, 0 }; static const float noise_offset[8]= { 0, 0, 0, 0, 0, 0, 0, 0 };