Copter: bug fix to accept HIL accel values correctly

This commit is contained in:
Randy Mackay 2013-03-19 11:32:43 +09:00 committed by rmackay9
parent 93fc9c48e5
commit b4b9d80c2f
1 changed files with 4 additions and 4 deletions

View File

@ -1913,9 +1913,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
accels.y = (float)packet.yacc / 1000.0;
accels.z = (float)packet.zacc / 1000.0;
ins.set_gyro_offsets(gyros);
ins.set_gyro(gyros);
ins.set_accel_offsets(accels);
ins.set_accel(accels);
// approximate a barometer
float y;
@ -1991,9 +1991,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
accels.y = (float)packet.yacc / 1000.0;
accels.z = (float)packet.zacc / 1000.0;
ins.set_gyro_offsets(gyros);
ins.set_gyro(gyros);
ins.set_accel_offsets(accels);
ins.set_accel(accels);
compass.setHIL(packet.xmag,packet.ymag,packet.zmag);
break;