aboutsummaryrefslogtreecommitdiff
path: root/apps/px4
diff options
context:
space:
mode:
Diffstat (limited to 'apps/px4')
-rw-r--r--apps/px4/attitude_estimator_bm/attitude_bm.c6
-rw-r--r--apps/px4/attitude_estimator_bm/attitude_estimator_bm.c12
2 files changed, 9 insertions, 9 deletions
diff --git a/apps/px4/attitude_estimator_bm/attitude_bm.c b/apps/px4/attitude_estimator_bm/attitude_bm.c
index cb17a356d..29908ddd5 100644
--- a/apps/px4/attitude_estimator_bm/attitude_bm.c
+++ b/apps/px4/attitude_estimator_bm/attitude_bm.c
@@ -147,9 +147,9 @@ void attitude_blackmagic_init(void)
// };
static m_elem kal_gain[12 * 9] = {
- 0.0006f , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0,
- 0 , 0.0006f , 0 , 0 , 0 , 0 , 0 , 0 , 0,
- 0 , 0 , 0.0006f , 0 , 0 , 0 , 0 , 0 , 0,
+ 0.001f , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0,
+ 0 , 0.001f , 0 , 0 , 0 , 0 , 0 , 0 , 0,
+ 0 , 0 , 0.001f , 0 , 0 , 0 , 0 , 0 , 0,
0 , 0 , 0 , 0.015f, 0 , 0 , 0 , 0 , 0,
0 , 0 , 0 , 0 , 0.015f, 0 , 0 , 0 , 0,
0 , 0 , 0 , 0 , 0 , 0.015f, 0 , 0 , 0,
diff --git a/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c b/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
index 97d7d39b7..1174a7524 100644
--- a/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
+++ b/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
@@ -87,14 +87,14 @@ int attitude_estimator_bm_update(struct sensor_combined_s *raw, float_vect3 *eul
gyro_values.z = raw->gyro_rad_s[2];
float_vect3 accel_values;
- accel_values.x = (raw->accelerometer_m_s2[0] / 9.81f) * 100;
- accel_values.y = (raw->accelerometer_m_s2[1] / 9.81f) * 100;
- accel_values.z = (raw->accelerometer_m_s2[2] / 9.81f) * 100;
+ accel_values.x = (raw->accelerometer_m_s2[0] / 9.81f) * 120;
+ accel_values.y = (raw->accelerometer_m_s2[1] / 9.81f) * 120;
+ accel_values.z = (raw->accelerometer_m_s2[2] / 9.81f) * 120;
float_vect3 mag_values;
- mag_values.x = raw->magnetometer_ga[0]*456.0f;
- mag_values.y = raw->magnetometer_ga[1]*456.0f;
- mag_values.z = raw->magnetometer_ga[2]*456.0f;
+ mag_values.x = raw->magnetometer_ga[0]*1500.0f;
+ mag_values.y = raw->magnetometer_ga[1]*1500.0f;
+ mag_values.z = raw->magnetometer_ga[2]*1500.0f;
// static int i = 0;