MAVLink: Use correct multi-instance syntax

This commit is contained in:
Lorenz Meier 2015-12-21 14:18:38 +01:00
parent 5d9048280f
commit 43aa6f64d9
1 changed files with 2 additions and 1 deletions

View File

@ -1178,7 +1178,8 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
tstatus.heartbeat_time = tstatus.timestamp;
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 {
orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);