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.cpp21
1 files changed, 11 insertions, 10 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index b1ba91cac..4d7b35f03 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -1043,10 +1043,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
gyro.temperature = imu.temperature;
if (_gyro_pub < 0) {
- _gyro_pub = orb_advertise(ORB_ID(sensor_gyro0), &gyro);
+ _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro);
} else {
- orb_publish(ORB_ID(sensor_gyro0), _gyro_pub, &gyro);
+ orb_publish(ORB_ID(sensor_gyro), _gyro_pub, &gyro);
}
}
@@ -1065,10 +1065,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
accel.temperature = imu.temperature;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
}
}
@@ -1086,10 +1086,11 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
mag.z = imu.zmag;
if (_mag_pub < 0) {
- _mag_pub = orb_advertise(ORB_ID(sensor_mag0), &mag);
+ /* publish to the first mag topic */
+ _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag);
} else {
- orb_publish(ORB_ID(sensor_mag0), _mag_pub, &mag);
+ orb_publish(ORB_ID(sensor_mag), _mag_pub, &mag);
}
}
@@ -1104,10 +1105,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
baro.temperature = imu.temperature;
if (_baro_pub < 0) {
- _baro_pub = orb_advertise(ORB_ID(sensor_baro0), &baro);
+ _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro);
} else {
- orb_publish(ORB_ID(sensor_baro0), _baro_pub, &baro);
+ orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro);
}
}
@@ -1394,10 +1395,10 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
accel.temperature = 25.0f;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
}
}