|
|
|
@ -1179,7 +1179,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
@@ -1179,7 +1179,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
|
|
|
|
|
|
|
|
|
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, &multi_instance, ORB_PRIO_HIGH); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus); |
|
|
|
|