MAVLink app: Adjust stack size of receiver thread

This commit is contained in:
Lorenz Meier
2015-03-08 08:14:58 +01:00
parent 54d2014bd6
commit ba0a343090

View File

@@ -1548,7 +1548,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 80;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2100);
pthread_attr_setstacksize(&receiveloop_attr, 1800);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);