Reduced optimistic send rates, better mag scaling

This commit is contained in:
Lorenz Meier
2012-08-20 12:38:45 +02:00
parent 0d28187960
commit aaf2a23f18
2 changed files with 9 additions and 9 deletions
+6 -6
View File
@@ -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);
@@ -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;