5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-10 18:08:30 -04:00

MAVLink: fixed another two places where micros() was used for a millisecond time

This commit is contained in:
Andrew Tridgell 2012-07-20 11:57:15 +10:00
parent 4f41b876b1
commit d0ebb4ca26
2 changed files with 4 additions and 4 deletions

View File

@ -84,7 +84,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
{
mavlink_msg_attitude_send(
chan,
micros(),
millis(),
ahrs.roll,
ahrs.pitch,
ahrs.yaw,
@ -418,7 +418,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
{
mavlink_msg_scaled_pressure_send(
chan,
micros(),
millis(),
(float)barometer.get_pressure()/100.0,
(float)(barometer.get_pressure() - barometer.get_ground_pressure())/100.0,
(int)(barometer.get_temperature()*10));

View File

@ -104,7 +104,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
Vector3f omega = ahrs.get_gyro();
mavlink_msg_attitude_send(
chan,
micros(),
millis(),
ahrs.roll,
ahrs.pitch - radians(g.pitch_trim*0.01),
ahrs.yaw,
@ -377,7 +377,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
int32_t pressure = barometer.get_pressure();
mavlink_msg_scaled_pressure_send(
chan,
micros(),
millis(),
pressure/100.0,
(pressure - barometer.get_ground_pressure())/100.0,
barometer.get_temperature());