forked from Archive/PX4-Autopilot
mavlink: fix pthread usage
This commit is contained in:
parent
5784f1d951
commit
aa0752ad86
|
@ -3184,7 +3184,7 @@ void MavlinkReceiver::start()
|
|||
pthread_attr_setstacksize(&receiveloop_attr,
|
||||
PX4_STACK_ADJUSTED(sizeof(MavlinkReceiver) + 2840 + MAVLINK_RECEIVER_NET_ADDED_STACK));
|
||||
|
||||
pthread_create(_thread, &receiveloop_attr, MavlinkReceiver::start_trampoline, this);
|
||||
pthread_create(&_thread, &receiveloop_attr, MavlinkReceiver::start_trampoline, (void *)this);
|
||||
|
||||
pthread_attr_destroy(&receiveloop_attr);
|
||||
}
|
||||
|
@ -3199,5 +3199,5 @@ void *MavlinkReceiver::start_trampoline(void *context)
|
|||
void MavlinkReceiver::stop()
|
||||
{
|
||||
_should_exit.store(true);
|
||||
pthread_join(*_thread, nullptr);
|
||||
pthread_join(_thread, nullptr);
|
||||
}
|
||||
|
|
|
@ -226,7 +226,7 @@ private:
|
|||
void update_rx_stats(const mavlink_message_t &message);
|
||||
|
||||
px4::atomic_bool _should_exit{false};
|
||||
pthread_t *_thread {};
|
||||
pthread_t _thread {};
|
||||
|
||||
Mavlink *_mavlink;
|
||||
|
||||
|
|
Loading…
Reference in New Issue