forked from Archive/PX4-Autopilot
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.
This commit is contained in:
parent
6c2c2b19a7
commit
fb4bf7c59c
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue