|
|
|
@ -355,9 +355,9 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
@@ -355,9 +355,9 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
|
|
|
|
|
mavlink_msg_raw_imu_send( |
|
|
|
|
chan, |
|
|
|
|
micros(), |
|
|
|
|
accel.x * 1000.0 / gravity, |
|
|
|
|
accel.y * 1000.0 / gravity, |
|
|
|
|
accel.z * 1000.0 / gravity, |
|
|
|
|
accel.x * 1000.0 / GRAVITY_MSS, |
|
|
|
|
accel.y * 1000.0 / GRAVITY_MSS, |
|
|
|
|
accel.z * 1000.0 / GRAVITY_MSS, |
|
|
|
|
gyro.x * 1000.0, |
|
|
|
|
gyro.y * 1000.0, |
|
|
|
|
gyro.z * 1000.0, |
|
|
|
@ -1647,9 +1647,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1647,9 +1647,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
|
|
|
|
|
// m/s/s |
|
|
|
|
Vector3f accels; |
|
|
|
|
accels.x = packet.xacc * (gravity/1000.0); |
|
|
|
|
accels.y = packet.yacc * (gravity/1000.0); |
|
|
|
|
accels.z = packet.zacc * (gravity/1000.0); |
|
|
|
|
accels.x = packet.xacc * (GRAVITY_MSS/1000.0); |
|
|
|
|
accels.y = packet.yacc * (GRAVITY_MSS/1000.0); |
|
|
|
|
accels.z = packet.zacc * (GRAVITY_MSS/1000.0); |
|
|
|
|
|
|
|
|
|
ins.set_gyro(gyros); |
|
|
|
|
|
|
|
|
|