diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c673ed28c8..a4b11726ba 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -2246,7 +2247,7 @@ MavlinkReceiver::receive_start(pthread_t *thread, Mavlink *parent) param.sched_priority = SCHED_PRIORITY_MAX - 80; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); - pthread_attr_setstacksize(&receiveloop_attr, 2100); + pthread_attr_setstacksize(&receiveloop_attr, PX4_STACK_ADJUSTED(2100)); pthread_create(thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent); pthread_attr_destroy(&receiveloop_attr);