mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
MAVLink: fixed another two places where micros() was used for a millisecond time
This commit is contained in:
parent
4f41b876b1
commit
d0ebb4ca26
@ -84,7 +84,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
|
|||||||
{
|
{
|
||||||
mavlink_msg_attitude_send(
|
mavlink_msg_attitude_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
millis(),
|
||||||
ahrs.roll,
|
ahrs.roll,
|
||||||
ahrs.pitch,
|
ahrs.pitch,
|
||||||
ahrs.yaw,
|
ahrs.yaw,
|
||||||
@ -418,7 +418,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
|
|||||||
{
|
{
|
||||||
mavlink_msg_scaled_pressure_send(
|
mavlink_msg_scaled_pressure_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
millis(),
|
||||||
(float)barometer.get_pressure()/100.0,
|
(float)barometer.get_pressure()/100.0,
|
||||||
(float)(barometer.get_pressure() - barometer.get_ground_pressure())/100.0,
|
(float)(barometer.get_pressure() - barometer.get_ground_pressure())/100.0,
|
||||||
(int)(barometer.get_temperature()*10));
|
(int)(barometer.get_temperature()*10));
|
||||||
|
@ -104,7 +104,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
|
|||||||
Vector3f omega = ahrs.get_gyro();
|
Vector3f omega = ahrs.get_gyro();
|
||||||
mavlink_msg_attitude_send(
|
mavlink_msg_attitude_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
millis(),
|
||||||
ahrs.roll,
|
ahrs.roll,
|
||||||
ahrs.pitch - radians(g.pitch_trim*0.01),
|
ahrs.pitch - radians(g.pitch_trim*0.01),
|
||||||
ahrs.yaw,
|
ahrs.yaw,
|
||||||
@ -377,7 +377,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
|
|||||||
int32_t pressure = barometer.get_pressure();
|
int32_t pressure = barometer.get_pressure();
|
||||||
mavlink_msg_scaled_pressure_send(
|
mavlink_msg_scaled_pressure_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
millis(),
|
||||||
pressure/100.0,
|
pressure/100.0,
|
||||||
(pressure - barometer.get_ground_pressure())/100.0,
|
(pressure - barometer.get_ground_pressure())/100.0,
|
||||||
barometer.get_temperature());
|
barometer.get_temperature());
|
||||||
|
Loading…
Reference in New Issue
Block a user