aboutsummaryrefslogtreecommitdiff
path: root/apps/px4
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-09-04 21:16:39 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-09-04 21:16:39 +0200
commite503c153617710452ec69c89c0d04b19cc710e7b (patch)
treed39448c73f22ab47c05acbc6271c3c4f18d18fb6 /apps/px4
parent62682d805ec234ecb4f5396ca2c7a072ce3f753c (diff)
downloadpx4-firmware-e503c153617710452ec69c89c0d04b19cc710e7b.tar.gz
px4-firmware-e503c153617710452ec69c89c0d04b19cc710e7b.tar.bz2
px4-firmware-e503c153617710452ec69c89c0d04b19cc710e7b.zip
Checkpoint - this is worth an AR.Drone flight test. Fixed thrust scaling in sensors for manual input, kind of fixed AR.Drone motor interface, very reliable now
Diffstat (limited to 'apps/px4')
-rw-r--r--apps/px4/attitude_estimator_bm/attitude_bm.c18
-rw-r--r--apps/px4/attitude_estimator_bm/attitude_estimator_bm.c6
2 files changed, 12 insertions, 12 deletions
diff --git a/apps/px4/attitude_estimator_bm/attitude_bm.c b/apps/px4/attitude_estimator_bm/attitude_bm.c
index 29908ddd5..8face5aea 100644
--- a/apps/px4/attitude_estimator_bm/attitude_bm.c
+++ b/apps/px4/attitude_estimator_bm/attitude_bm.c
@@ -147,18 +147,18 @@ void attitude_blackmagic_init(void)
// };
static m_elem kal_gain[12 * 9] = {
- 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,
+ 0.0007f , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0,
+ 0 , 0.0007f , 0 , 0 , 0 , 0 , 0 , 0 , 0,
+ 0 , 0 , 0.0007f , 0 , 0 , 0 , 0 , 0 , 0,
+ 0 , 0 , 0 , 0.01f, 0 , 0 , 0 , 0 , 0,
+ 0 , 0 , 0 , 0 , 0.01f, 0 , 0 , 0 , 0,
+ 0 , 0 , 0 , 0 , 0 , 0.01f, 0 , 0 , 0,
0.0000f , +0.00002f, 0 , 0 , 0, 0, 0, 0 , 0,
-0.00002f, 0 , 0 , 0 , 0, 0, 0, 0, 0,
0, 0 , 0 , 0, 0, 0, 0, 0, 0,
- 0 , 0 , 0 , 0 , 0 , 0 , 0.6f , 0 , 0,
- 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.6f , 0,
- 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.6f
+ 0 , 0 , 0 , 0 , 0 , 0 , 0.4f , 0 , 0,
+ 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.4f , 0,
+ 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.4f
};
//offset update only correct if not upside down.
diff --git a/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c b/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
index 1174a7524..0f6b6044f 100644
--- a/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
+++ b/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
@@ -87,9 +87,9 @@ 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) * 120;
- accel_values.y = (raw->accelerometer_m_s2[1] / 9.81f) * 120;
- accel_values.z = (raw->accelerometer_m_s2[2] / 9.81f) * 120;
+ 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;
float_vect3 mag_values;
mag_values.x = raw->magnetometer_ga[0]*1500.0f;