diff options
Diffstat (limited to 'apps/mavlink')
-rw-r--r-- | apps/mavlink/mavlink.c | 8 |
1 files changed, 3 insertions, 5 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index c151d791b..9fc987910 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -425,7 +425,6 @@ static void *receiveloop(void *arg) /* Handle packet with parameter component */ mavlink_pm_message_handler(MAVLINK_COMM_0, &msg); - msg.msgid = -1; } } @@ -967,7 +966,6 @@ void handleMessage(mavlink_message_t *msg) */ // printf("\n HIL ENABLED?: %s \n",(mavlink_hil_enabled)?"true":"false"); -#define DEG2RAD ((1.0/180.0)*M_PI) if (mavlink_hil_enabled) { @@ -1270,13 +1268,13 @@ int mavlink_main(int argc, char *argv[]) pthread_attr_t receiveloop_attr; pthread_attr_init(&receiveloop_attr); - pthread_attr_setstacksize(&receiveloop_attr, 4096); + pthread_attr_setstacksize(&receiveloop_attr, 2048); pthread_create(&receive_thread, &receiveloop_attr, receiveloop, NULL); pthread_attr_t uorb_attr; pthread_attr_init(&uorb_attr); - /* Set stack size, needs more than 5000 bytes */ - pthread_attr_setstacksize(&uorb_attr, 7000); + /* Set stack size, needs more than 4000 bytes */ + pthread_attr_setstacksize(&uorb_attr, 4096); pthread_create(&uorb_receive_thread, &uorb_attr, uorb_receiveloop, NULL); /* initialize waypoint manager */ |