mavlink app: Reduce stack sizes minimally after further inspection

This commit is contained in:
Lorenz Meier
2014-05-16 10:47:18 +02:00
parent 9d2bfb596c
commit cccd3e1dc4
2 changed files with 2 additions and 2 deletions
+1 -1
View File
@@ -2204,7 +2204,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
1950,
(main_t)&Mavlink::start_helper,
(const char **)argv);
+1 -1
View File
@@ -949,7 +949,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 3000);
pthread_attr_setstacksize(&receiveloop_attr, 2900);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);