forked from Archive/PX4-Autopilot
MAVLink: Use correct multi-instance syntax
This commit is contained in:
parent
5d9048280f
commit
43aa6f64d9
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue