mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Do not receive anything in OSD mode
This commit is contained in:
parent
b600e3ee93
commit
e26c5bb590
@ -143,7 +143,7 @@ Mavlink::Mavlink() :
|
||||
_radio_id(0),
|
||||
_logbuffer(5, sizeof(mavlink_log_s)),
|
||||
_total_counter(0),
|
||||
_receive_thread {},
|
||||
_receive_thread{},
|
||||
_verbose(false),
|
||||
_forwarding_on(false),
|
||||
_ftp_on(false),
|
||||
@ -1629,7 +1629,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
mavlink_update_system();
|
||||
|
||||
/* start the MAVLink receiver */
|
||||
MavlinkReceiver::receive_start(&_receive_thread, this);
|
||||
if (_mode != MAVLINK_MODE_OSD) {
|
||||
MavlinkReceiver::receive_start(&_receive_thread, this);
|
||||
}
|
||||
|
||||
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
|
||||
uint64_t param_time = 0;
|
||||
@ -1989,7 +1991,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
/* first wait for threads to complete before tearing down anything */
|
||||
pthread_join(_receive_thread, NULL);
|
||||
if (_mode != MAVLINK_MODE_OSD) {
|
||||
pthread_join(_receive_thread, NULL);
|
||||
}
|
||||
|
||||
delete _subscribe_to_stream;
|
||||
_subscribe_to_stream = nullptr;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user