Move MAVLink to multi pub/sub API (to first index)

This commit is contained in:
Lorenz Meier
2015-01-25 21:07:31 +01:00
parent c4cf28fa95
commit 165e5f5a62

View File

@@ -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);
}
}
@@ -1105,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);
}
}
@@ -1395,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);
}
}