Browse Source

MAVLink: Use correct multi-instance syntax

sbg
Lorenz Meier 9 years ago
parent
commit
43aa6f64d9
  1. 3
      src/modules/mavlink/mavlink_receiver.cpp

3
src/modules/mavlink/mavlink_receiver.cpp

@ -1178,7 +1178,8 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
tstatus.heartbeat_time = tstatus.timestamp; tstatus.heartbeat_time = tstatus.timestamp;
if (_telemetry_status_pub == nullptr) { if (_telemetry_status_pub == nullptr) {
_telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, NULL, ORB_PRIO_HIGH); int multi_instance;
_telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, multi_instance, ORB_PRIO_HIGH);
} else { } else {
orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus); orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);

Loading…
Cancel
Save