Browse Source

Fixed incorrect scaling of acceleration values

sbg
Lorenz Meier 13 years ago
parent
commit
2a5fcd9174
  1. 4
      apps/mavlink/mavlink.c
  2. 6
      apps/px4/attitude_estimator_bm/attitude_estimator_bm.c
  3. 6
      apps/sensors/sensors.c

4
apps/mavlink/mavlink.c

@ -635,8 +635,8 @@ static void *uorb_receiveloop(void *arg) @@ -635,8 +635,8 @@ static void *uorb_receiveloop(void *arg)
/* send raw imu data */
mavlink_msg_raw_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_raw[0], buf.raw.accelerometer_raw[1], buf.raw.accelerometer_raw[2], buf.raw.gyro_raw[0], buf.raw.gyro_raw[1], buf.raw.gyro_raw[2], buf.raw.magnetometer_raw[0], buf.raw.magnetometer_raw[1], buf.raw.magnetometer_raw[2]);
/* send scaled imu data */
mavlink_msg_scaled_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_m_s2[0] * 9810, buf.raw.accelerometer_m_s2[1] * 9810, buf.raw.accelerometer_m_s2[2] * 9810, buf.raw.gyro_rad_s[0] * 1000, buf.raw.gyro_rad_s[1] * 1000, buf.raw.gyro_rad_s[2] * 1000, buf.raw.magnetometer_ga[0] * 1000, buf.raw.magnetometer_ga[1] * 1000, buf.raw.magnetometer_ga[2] * 1000);
/* send scaled imu data (m/s^2 accelerations scaled back to milli-g) */
mavlink_msg_scaled_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_m_s2[0] * 101.936799f, buf.raw.accelerometer_m_s2[1] * 101.936799f, buf.raw.accelerometer_m_s2[2] * 101.936799f, buf.raw.gyro_rad_s[0] * 1000, buf.raw.gyro_rad_s[1] * 1000, buf.raw.gyro_rad_s[2] * 1000, buf.raw.magnetometer_ga[0] * 1000, buf.raw.magnetometer_ga[1] * 1000, buf.raw.magnetometer_ga[2] * 1000);
/* send pressure */
mavlink_msg_scaled_pressure_send(MAVLINK_COMM_0, buf.raw.timestamp / 1000, buf.raw.baro_pres_mbar, buf.raw.baro_alt_meter, buf.raw.baro_temp_celcius * 100);

6
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 @@ -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];
accel_values.y = raw->accelerometer_m_s2[1];
accel_values.z = raw->accelerometer_m_s2[2];
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;
float_vect3 mag_values;
mag_values.x = raw->magnetometer_ga[0]*100.0f;

6
apps/sensors/sensors.c

@ -819,9 +819,9 @@ int sensors_thread_main(int argc, char *argv[]) @@ -819,9 +819,9 @@ int sensors_thread_main(int argc, char *argv[])
// XXX read range from sensor
float range_g = 4.0f;
/* scale from 14 bit to m/s2 */
raw.accelerometer_m_s2[0] = (((raw.accelerometer_raw[0] - acc_offset[0]) * range_g) / 8192.0f) / 9.81f;
raw.accelerometer_m_s2[1] = (((raw.accelerometer_raw[1] - acc_offset[1]) * range_g) / 8192.0f) / 9.81f;
raw.accelerometer_m_s2[2] = (((raw.accelerometer_raw[2] - acc_offset[2]) * range_g) / 8192.0f) / 9.81f;
raw.accelerometer_m_s2[0] = (((raw.accelerometer_raw[0] - acc_offset[0]) / 8192.0f) * range_g) * 9.81f;
raw.accelerometer_m_s2[1] = (((raw.accelerometer_raw[1] - acc_offset[1]) / 8192.0f) * range_g) * 9.81f;
raw.accelerometer_m_s2[2] = (((raw.accelerometer_raw[2] - acc_offset[2]) / 8192.0f) * range_g) * 9.81f;
raw.accelerometer_raw_counter++;
}

Loading…
Cancel
Save