aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_receiver.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/mavlink_receiver.cpp')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp10
1 files changed, 4 insertions, 6 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index c222a3ddf..876466449 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -109,7 +109,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_rc_pub(-1),
_manual_pub(-1),
- _hil_counter(0),
_hil_frames(0),
_old_timestamp(0),
_hil_local_proj_inited(0),
@@ -586,7 +585,6 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_sensors.gyro_rad_s[0] = imu.xgyro;
hil_sensors.gyro_rad_s[1] = imu.ygyro;
hil_sensors.gyro_rad_s[2] = imu.zgyro;
- hil_sensors.gyro_counter = _hil_counter;
hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
@@ -596,7 +594,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
hil_sensors.accelerometer_mode = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
- hil_sensors.accelerometer_counter = _hil_counter;
+ hil_sensors.accelerometer_timestamp = timestamp;
hil_sensors.adc_voltage_v[0] = 0.0f;
hil_sensors.adc_voltage_v[1] = 0.0f;
@@ -611,15 +609,15 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_sensors.magnetometer_range_ga = 32.7f; // int16
hil_sensors.magnetometer_mode = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
- hil_sensors.magnetometer_counter = _hil_counter;
+ hil_sensors.magnetometer_timestamp = timestamp;
hil_sensors.baro_pres_mbar = imu.abs_pressure;
hil_sensors.baro_alt_meter = imu.pressure_alt;
hil_sensors.baro_temp_celcius = imu.temperature;
- hil_sensors.baro_counter = _hil_counter;
+ hil_sensors.baro_timestamp = timestamp;
hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
- hil_sensors.differential_pressure_counter = _hil_counter;
+ hil_sensors.differential_pressure_timestamp = timestamp;
/* publish combined sensor topic */
if (_sensors_pub > 0) {