From aaf2a23f18eb802c9fea1e45199106eefbab59f3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 20 Aug 2012 12:38:45 +0200 Subject: [PATCH] Reduced optimistic send rates, better mag scaling --- apps/mavlink/mavlink.c | 12 ++++++------ .../attitude_estimator_bm/attitude_estimator_bm.c | 6 +++--- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index b667269ede..7fba65cb73 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -1318,17 +1318,17 @@ int mavlink_thread_main(int argc, char *argv[]) /* all subscriptions are now active, set up initial guess about rate limits */ if (baudrate >= 921600) { - /* set no limit */ /* 500 Hz / 2 ms */ - //set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 2); + set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 2); + set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 2); } else if (baudrate >= 460800) { /* 250 Hz / 4 ms */ - set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 4); - set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 4); + set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 5); + set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 5); } else if (baudrate >= 115200) { /* 50 Hz / 20 ms */ - set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 20); - set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 20); + set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 50); + set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 50); } else if (baudrate >= 57600) { /* 10 Hz / 100 ms */ set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 100); diff --git a/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c b/apps/px4/attitude_estimator_bm/attitude_estimator_bm.c index 1e2e6b6253..feaed66954 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; - accel_values.y = raw->accelerometer_m_s2[1] * 9.81f; - accel_values.z = raw->accelerometer_m_s2[2] * 9.81f; + accel_values.x = raw->accelerometer_m_s2[0] * 9.81f * 9.0f; + accel_values.y = raw->accelerometer_m_s2[1] * 9.81f * 9.0f; + accel_values.z = raw->accelerometer_m_s2[2] * 9.81f * 9.0f; float_vect3 mag_values; mag_values.x = raw->magnetometer_ga[0]*510.0f;