Browse Source

Stack size reduced to 1816. Max stack reported by top was 1448 under HIL.

sbg
Darryl Taylor 11 years ago
parent
commit
58a1f19d79
  1. 2
      src/modules/mavlink/mavlink_receiver.cpp

2
src/modules/mavlink/mavlink_receiver.cpp

@ -871,7 +871,7 @@ receive_start(int uart)
param.sched_priority = SCHED_PRIORITY_MAX - 40; param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param); (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 3000); pthread_attr_setstacksize(&receiveloop_attr, 1816);
pthread_t thread; pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart); pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);

Loading…
Cancel
Save