From fb4bf7c59c47f9dd536dd4df87252b7d51727afe Mon Sep 17 00:00:00 2001 From: Erik de Castro Lopo Date: Fri, 27 Nov 2015 16:01:06 +1100 Subject: [PATCH] MAVLink: Fix call to orb_advertise_multi Previously, pointer to an uninitialized int was being passed as the instance pointer. Now we pass a NULL pointer instead and the code being called will use the default instance value of zero. --- src/modules/mavlink/mavlink_receiver.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index d139ac99dd..37d070718d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1183,8 +1183,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) tstatus.heartbeat_time = tstatus.timestamp; if (_telemetry_status_pub == nullptr) { - int multi_instance; - _telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, &multi_instance, ORB_PRIO_HIGH); + _telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, NULL, ORB_PRIO_HIGH); } else { orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);