|
|
|
@ -643,28 +643,28 @@ protected:
@@ -643,28 +643,28 @@ protected:
|
|
|
|
|
if (_sensor_sub->update(&_sensor_time, &sensor)) { |
|
|
|
|
uint16_t fields_updated = 0; |
|
|
|
|
|
|
|
|
|
if (_accel_timestamp != sensor.accelerometer_timestamp) { |
|
|
|
|
if (_accel_timestamp != sensor.accelerometer_timestamp[0]) { |
|
|
|
|
/* mark first three dimensions as changed */ |
|
|
|
|
fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); |
|
|
|
|
_accel_timestamp = sensor.accelerometer_timestamp; |
|
|
|
|
_accel_timestamp = sensor.accelerometer_timestamp[0]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_gyro_timestamp != sensor.timestamp) { |
|
|
|
|
if (_gyro_timestamp != sensor.gyro_timestamp[0]) { |
|
|
|
|
/* mark second group dimensions as changed */ |
|
|
|
|
fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); |
|
|
|
|
_gyro_timestamp = sensor.timestamp; |
|
|
|
|
_gyro_timestamp = sensor.gyro_timestamp[0]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_mag_timestamp != sensor.magnetometer_timestamp) { |
|
|
|
|
if (_mag_timestamp != sensor.magnetometer_timestamp[0]) { |
|
|
|
|
/* mark third group dimensions as changed */ |
|
|
|
|
fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); |
|
|
|
|
_mag_timestamp = sensor.magnetometer_timestamp; |
|
|
|
|
_mag_timestamp = sensor.magnetometer_timestamp[0]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_baro_timestamp != sensor.baro_timestamp) { |
|
|
|
|
if (_baro_timestamp != sensor.baro_timestamp[0]) { |
|
|
|
|
/* mark last group dimensions as changed */ |
|
|
|
|
fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); |
|
|
|
|
_baro_timestamp = sensor.baro_timestamp; |
|
|
|
|
_baro_timestamp = sensor.baro_timestamp[0]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
mavlink_highres_imu_t msg; |
|
|
|
@ -679,10 +679,10 @@ protected:
@@ -679,10 +679,10 @@ protected:
|
|
|
|
|
msg.xmag = sensor.magnetometer_ga[0]; |
|
|
|
|
msg.ymag = sensor.magnetometer_ga[1]; |
|
|
|
|
msg.zmag = sensor.magnetometer_ga[2]; |
|
|
|
|
msg.abs_pressure = sensor.baro_pres_mbar; |
|
|
|
|
msg.diff_pressure = sensor.differential_pressure_pa; |
|
|
|
|
msg.pressure_alt = sensor.baro_alt_meter; |
|
|
|
|
msg.temperature = sensor.baro_temp_celcius; |
|
|
|
|
msg.abs_pressure = sensor.baro_pres_mbar[0]; |
|
|
|
|
msg.diff_pressure = sensor.differential_pressure_pa[0]; |
|
|
|
|
msg.pressure_alt = sensor.baro_alt_meter[0]; |
|
|
|
|
msg.temperature = sensor.baro_temp_celcius[0]; |
|
|
|
|
msg.fields_updated = fields_updated; |
|
|
|
|
|
|
|
|
|
_mavlink->send_message(MAVLINK_MSG_ID_HIGHRES_IMU, &msg); |
|
|
|
|