diff --git a/platforms/posix/include/px4_daemon/server_io.h b/platforms/posix/include/px4_daemon/server_io.h index 88c417501dea2ec81065328017d40c6ad813028a..efeae545b8610ee53052989bdd409b3d5fd36c8d 100644 --- a/platforms/posix/include/px4_daemon/server_io.h +++ b/platforms/posix/include/px4_daemon/server_io.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * Copyright (C) 2018 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,11 +33,7 @@ /** * @file server_io.h * - * These are helper functions to send the stdout over a pipe - * back to the client. - * - * @author Julian Oes <julian@oes.ch> - * @author Beat Küng <beat-kueng@gmx.net> + * @author Mara Bos <m-ou.se@m-ou.se> */ #pragma once @@ -46,20 +42,11 @@ __BEGIN_DECLS /** - * Get the stdout pipe buffer in order to write to fill it. + * Get the stdout of the current thread. * - * @param buffer: pointer to buffer that will be set in function. - * @param max_length: length of the assigned buffer. - * @param is_atty: true if we are writing to a terminal (and can e.g. use colors). - * @return 0 on success + * @param isatty_: if not NULL, *isatty_ will be set to wether the stream points to a terminal (true) or not (false). + * @return The FILE* which represents the standard output of the current thread. */ -__EXPORT int get_stdout_pipe_buffer(char **buffer, unsigned *max_length, bool *is_atty); +__EXPORT FILE *get_stdout(bool *isatty_); -/** - * Write the filled bytes to the pipe. - * - * @param buffer_length: the number of bytes that should be written. - * @return 0 on success - */ -__EXPORT int send_stdout_pipe_buffer(unsigned buffer_length); __END_DECLS diff --git a/platforms/posix/src/px4_daemon/client.cpp b/platforms/posix/src/px4_daemon/client.cpp index f6604b9566cbd5ae5e1f9391725061ac498cb0b6..6266489a5e8827e6d182694a2527c37f1c54073f 100644 --- a/platforms/posix/src/px4_daemon/client.cpp +++ b/platforms/posix/src/px4_daemon/client.cpp @@ -46,6 +46,7 @@ #include <sys/socket.h> #include <sys/stat.h> #include <sys/un.h> +#include <unistd.h> #include <string> diff --git a/platforms/posix/src/px4_daemon/server.cpp b/platforms/posix/src/px4_daemon/server.cpp index d327385507cdb276242dba3190ee3c1a146544e6..6df0507ccd85025bce03f761c9f6c951c8a88f24 100644 --- a/platforms/posix/src/px4_daemon/server.cpp +++ b/platforms/posix/src/px4_daemon/server.cpp @@ -40,6 +40,7 @@ #include <errno.h> #include <fcntl.h> +#include <stdio.h> #include <unistd.h> #include <string.h> #include <string> @@ -141,6 +142,10 @@ Server::_server_main() // Watch the listening socket for incoming connections. poll_fds.push_back(pollfd {_fd, POLLIN, 0}); + // The list of FILE pointers that we'll need to fclose(). + // stdouts[i] corresponds to poll_fds[i+1]. + std::vector<FILE *> stdouts; + while (true) { int n_ready = poll(poll_fds.data(), poll_fds.size(), -1); @@ -162,22 +167,36 @@ Server::_server_main() return; } - // Start a new thread to handle the client. - pthread_t *thread = &_fd_to_thread[client]; - ret = pthread_create(thread, nullptr, Server::_handle_client, (void *)(intptr_t)client); + FILE *thread_stdout = fdopen(client, "w"); - if (ret != 0) { - PX4_ERR("could not start pthread (%i)", ret); - _fd_to_thread.erase(client); + if (thread_stdout == nullptr) { + PX4_ERR("could not open stdout for new thread"); close(client); } else { - // We won't join the thread, so detach to automatically release resources at its end - pthread_detach(*thread); - } + // Set stream to line buffered. + setvbuf(thread_stdout, nullptr, _IOLBF, BUFSIZ); + + // Start a new thread to handle the client. + pthread_t *thread = &_fd_to_thread[client]; + ret = pthread_create(thread, nullptr, Server::_handle_client, thread_stdout); + + if (ret != 0) { + PX4_ERR("could not start pthread (%i)", ret); + _fd_to_thread.erase(client); + fclose(thread_stdout); + + } else { + // We won't join the thread, so detach to automatically release resources at its end + pthread_detach(*thread); - // Start listening for the client hanging up. - poll_fds.push_back(pollfd {client, POLLHUP, 0}); + // Start listening for the client hanging up. + poll_fds.push_back(pollfd {client, POLLHUP, 0}); + + // Remember the FILE *, so we can fclose() it later. + stdouts.push_back(thread_stdout); + } + } } // Handle any closed connections. @@ -193,7 +212,8 @@ Server::_server_main() _fd_to_thread.erase(thread); } - close(poll_fds[i].fd); + fclose(stdouts[i - 1]); + stdouts.erase(stdouts.begin() + i - 1); poll_fds.erase(poll_fds.begin() + i); } else { @@ -210,7 +230,8 @@ Server::_server_main() void *Server::_handle_client(void *arg) { - int fd = (int)(intptr_t)arg; + FILE *out = (FILE *)arg; + int fd = fileno(out); // Read until the end of the incoming stream. std::string cmd; @@ -247,7 +268,7 @@ void if ((thread_data_ptr = (CmdThreadSpecificData *)pthread_getspecific(_instance->_key)) == nullptr) { thread_data_ptr = new CmdThreadSpecificData; - thread_data_ptr->fd = fd; + thread_data_ptr->thread_stdout = out; thread_data_ptr->is_atty = isatty; (void)pthread_setspecific(_instance->_key, (void *)thread_data_ptr); @@ -259,10 +280,13 @@ void // Report return value. char buf[2] = {0, (char)retval}; - if (write(fd, buf, sizeof buf) < 0) { + if (fwrite(buf, sizeof buf, 1, out) != 1) { // Don't care it went wrong, as we're cleaning up anyway. } + // Flush the FILE*'s buffer before we shut down the connection. + fflush(out); + _cleanup(fd); return nullptr; } diff --git a/platforms/posix/src/px4_daemon/server.h b/platforms/posix/src/px4_daemon/server.h index 1ce8d0767595413dd2274e49f983ea58336d0682..2932a977ff29c0bcb8244c84f6dfc1b71740f4bc 100644 --- a/platforms/posix/src/px4_daemon/server.h +++ b/platforms/posix/src/px4_daemon/server.h @@ -49,6 +49,7 @@ */ #pragma once +#include <stdio.h> #include <stdint.h> #include <stdbool.h> #include <pthread.h> @@ -75,9 +76,8 @@ public: int start(); struct CmdThreadSpecificData { - int fd; // fd to send stdout to + FILE *thread_stdout; // stdout of this thread bool is_atty; // whether file descriptor refers to a terminal - char buffer[1024]; }; static bool is_running() diff --git a/platforms/posix/src/px4_daemon/server_io.cpp b/platforms/posix/src/px4_daemon/server_io.cpp index ba801053da4498031ea794f2e249d1fcbf699bff..381bea9be15e25f83022eba6b6986fef792bac6b 100644 --- a/platforms/posix/src/px4_daemon/server_io.cpp +++ b/platforms/posix/src/px4_daemon/server_io.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * Copyright (C) 2016-2018 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -35,8 +35,10 @@ * * @author Julian Oes <julian@oes.ch> * @author Beat Küng <beat-kueng@gmx.net> + * @author Mara Bos <m-ou.se@m-ou.se> */ +#include <stdio.h> #include <fcntl.h> #include <unistd.h> #include <string> @@ -56,21 +58,19 @@ using namespace px4_daemon; -int get_stdout_pipe_buffer(char **buffer, unsigned *max_length, bool *is_atty) +FILE *get_stdout(bool *isatty_) { - // The thread specific data won't be initialized if the server is not running. Server::CmdThreadSpecificData *thread_data_ptr; - if (!Server::is_running()) { - return -1; - } - // If we are not in a thread that has been started by a client, we don't // have any thread specific data set and we won't have a pipe to write // stdout to. - if ((thread_data_ptr = (Server::CmdThreadSpecificData *)pthread_getspecific( + if (!Server::is_running() || + (thread_data_ptr = (Server::CmdThreadSpecificData *)pthread_getspecific( Server::get_pthread_key())) == nullptr) { - return -1; + if (isatty_) { *isatty_ = isatty(1); } + + return stdout; } #ifdef __PX4_POSIX_EAGLE @@ -79,37 +79,20 @@ int get_stdout_pipe_buffer(char **buffer, unsigned *max_length, bool *is_atty) // even though the pthread_key has been created. // We can catch this using the check below but we have no clue why this happens. if (thread_data_ptr == (void *)0x1) { - return -1; + if (isatty_) { *isatty_ = isatty(1); } + + return stdout; } #endif - *buffer = thread_data_ptr->buffer; - *max_length = sizeof(thread_data_ptr->buffer); - *is_atty = thread_data_ptr->is_atty; - - return 0; -} - -int send_stdout_pipe_buffer(unsigned buffer_length) -{ - Server::CmdThreadSpecificData *thread_data_ptr; + if (thread_data_ptr->thread_stdout == nullptr) { + if (isatty_) { *isatty_ = isatty(1); } - if (!Server::is_running()) { - return -1; + return stdout; } - if ((thread_data_ptr = (Server::CmdThreadSpecificData *)pthread_getspecific( - Server::get_pthread_key())) == nullptr) { - return -1; - } - - int bytes_sent = write(thread_data_ptr->fd, thread_data_ptr->buffer, buffer_length); - - if (bytes_sent != (int)buffer_length) { - printf("write fail\n"); - return -1; - } + if (isatty_) { *isatty_ = thread_data_ptr->is_atty; } - return 0; + return thread_data_ptr->thread_stdout; } diff --git a/src/drivers/linux_pwm_out/navio_sysfs.cpp b/src/drivers/linux_pwm_out/navio_sysfs.cpp index 4b5c992cc87ac748c13df3d4e2390d10884a19c2..8b00f499531cdd1049a7009e5d438210d411ed5a 100644 --- a/src/drivers/linux_pwm_out/navio_sysfs.cpp +++ b/src/drivers/linux_pwm_out/navio_sysfs.cpp @@ -35,6 +35,7 @@ #include <fcntl.h> #include <errno.h> +#include <unistd.h> #include <px4_log.h> using namespace linux_pwm_out; diff --git a/src/drivers/linux_pwm_out/ocpoc_mmap.cpp b/src/drivers/linux_pwm_out/ocpoc_mmap.cpp index c301f77be19e728acc9ecbac52f69dab14eb9d0e..991aa553007030f0c719e52255892a2fd6f624af 100644 --- a/src/drivers/linux_pwm_out/ocpoc_mmap.cpp +++ b/src/drivers/linux_pwm_out/ocpoc_mmap.cpp @@ -37,6 +37,7 @@ #include <fcntl.h> #include <sys/mman.h> +#include <unistd.h> using namespace linux_pwm_out; diff --git a/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp b/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp index d53003b4f9c1fe5eae1135bfd72b52279659dfc2..18081a09ff440d704db78fecb100c99315829718 100644 --- a/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp +++ b/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp @@ -37,6 +37,7 @@ #include <fcntl.h> #include <stdio.h> #include <stdint.h> +#include <unistd.h> #include <px4_config.h> #include <px4_workqueue.h> diff --git a/src/drivers/rpi_rc_in/rpi_rc_in.h b/src/drivers/rpi_rc_in/rpi_rc_in.h index def9f74a47804cc85a54930c07f0b9c8fda862b2..b301d8fab26e67985a36d2797b34e1b6f0dc97dd 100644 --- a/src/drivers/rpi_rc_in/rpi_rc_in.h +++ b/src/drivers/rpi_rc_in/rpi_rc_in.h @@ -46,6 +46,7 @@ #include <fcntl.h> #include <stdio.h> #include <stdint.h> +#include <unistd.h> #include <px4_config.h> #include <px4_workqueue.h> diff --git a/src/modules/logger/util.cpp b/src/modules/logger/util.cpp index 9d6513927c4936c3a6254b059158fac1f45ad50b..958369c062d6c80f68d64009f3f866b01a7c5279 100644 --- a/src/modules/logger/util.cpp +++ b/src/modules/logger/util.cpp @@ -37,6 +37,7 @@ #include <sys/stat.h> #include <string.h> #include <stdlib.h> +#include <unistd.h> #include <uORB/topics/vehicle_gps_position.h> diff --git a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp index a029ec7cd3bf9459d355aa491e2d95bcea88142f..bb54d92bbf16cf21d5bb5a8c439823ce2fe1e8b1 100644 --- a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp +++ b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp @@ -37,6 +37,7 @@ #include "../uORB.h" #include <px4_time.h> #include <px4_tasks.h> +#include <unistd.h> struct orb_test { int val; diff --git a/src/platforms/common/CMakeLists.txt b/src/platforms/common/CMakeLists.txt index 60963668a93cafce357987b9d64f3253d77548e2..fcd2eb5b04c35982ac0754dd4580d2b4702b9f4a 100644 --- a/src/platforms/common/CMakeLists.txt +++ b/src/platforms/common/CMakeLists.txt @@ -33,7 +33,7 @@ set(SRCS) -if (NOT "${OS}" MATCHES "qurt") +if (NOT "${OS}" MATCHES "qurt" AND NOT "${CONFIG}" MATCHES "px4io") list(APPEND SRCS px4_log.c ) diff --git a/src/platforms/common/px4_log.c b/src/platforms/common/px4_log.c index 5476162f91601a0c1b8588e797f2f0d8f0ff5c85..850710121ab0966daa279a689bdb274a928a8c85 100644 --- a/src/platforms/common/px4_log.c +++ b/src/platforms/common/px4_log.c @@ -31,6 +31,7 @@ * ****************************************************************************/ +#include <stdio.h> #include <stdlib.h> #include <string.h> #include <px4_log.h> @@ -95,78 +96,38 @@ void px4_backtrace() __EXPORT void px4_log_modulename(int level, const char *moduleName, const char *fmt, ...) { + FILE *out = stdout; + bool use_color = true; #ifdef __PX4_POSIX - char *buffer; - unsigned max_length; - bool is_atty = false; - - if (get_stdout_pipe_buffer(&buffer, &max_length, &is_atty) == 0) { - if (level >= _PX4_LOG_LEVEL_INFO) { - - unsigned pos = 0; - - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", __px4_log_level_color[level]); } - - if (pos >= max_length) { return; } - - pos += snprintf(buffer + pos, max_length - pos, __px4__log_level_fmt __px4__log_level_arg(level)); - - if (pos >= max_length) { return; } - - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", PX4_ANSI_COLOR_GRAY); } - - if (pos >= max_length) { return; } - - pos += snprintf(buffer + pos, max_length - pos, __px4__log_modulename_pfmt, moduleName); - va_list argptr; - - if (pos >= max_length) { return; } - - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", __px4_log_level_color[level]); } - - if (pos >= max_length) { return; } - - va_start(argptr, fmt); - pos += vsnprintf(buffer + pos, max_length - pos, fmt, argptr); + out = get_stdout(&use_color); +#endif - if (pos >= max_length) { return; } +#ifndef PX4_LOG_COLORIZED_OUTPUT + use_color = false; +#endif - va_end(argptr); - pos += snprintf(buffer + pos, max_length - pos, "\n"); + if (level >= _PX4_LOG_LEVEL_INFO) { + if (use_color) { fputs(__px4_log_level_color[level], out); } - if (pos >= max_length) { return; } + fprintf(out, __px4__log_level_fmt __px4__log_level_arg(level)); - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", PX4_ANSI_COLOR_RESET); } + if (use_color) { fputs(PX4_ANSI_COLOR_GRAY, out); } - if (pos >= max_length) { return; } + fprintf(out, __px4__log_modulename_pfmt, moduleName); - // +1 for the terminating 0 char. - send_stdout_pipe_buffer(pos + 1); - } + if (use_color) { fputs(__px4_log_level_color[level], out); } - } else { -#endif + va_list argptr; + va_start(argptr, fmt); + vfprintf(out, fmt, argptr); + va_end(argptr); - if (level >= _PX4_LOG_LEVEL_INFO) { - PX4_LOG_COLOR_START - printf(__px4__log_level_fmt __px4__log_level_arg(level)); - PX4_LOG_COLOR_MODULE - printf(__px4__log_modulename_pfmt, moduleName); - PX4_LOG_COLOR_MESSAGE - va_list argptr; - va_start(argptr, fmt); - vprintf(fmt, argptr); - va_end(argptr); - PX4_LOG_COLOR_END - printf("\n"); - } + if (use_color) { fputs(PX4_ANSI_COLOR_RESET, out); } -#ifdef __PX4_POSIX + fputc('\n', out); } -#endif - /* publish an orb log message */ if (level >= _PX4_LOG_LEVEL_WARN && orb_log_message_pub) { //only publish important messages @@ -201,52 +162,25 @@ __EXPORT void px4_log_modulename(int level, const char *moduleName, const char * __EXPORT void px4_log_raw(int level, const char *fmt, ...) { + FILE *out = stdout; + bool use_color = true; #ifdef __PX4_POSIX - char *buffer; - unsigned max_length; - bool is_atty = false; - - if (get_stdout_pipe_buffer(&buffer, &max_length, &is_atty) == 0) { - if (level >= _PX4_LOG_LEVEL_INFO) { - - unsigned pos = 0; - - va_list argptr; - - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", __px4_log_level_color[level]); } - - if (pos >= max_length) { return; } - - va_start(argptr, fmt); - pos += vsnprintf(buffer + pos, max_length - pos, fmt, argptr); - va_end(argptr); - - if (pos >= max_length) { return; } - - if (is_atty) { pos += snprintf(buffer + pos, max_length - pos, "%s", PX4_ANSI_COLOR_RESET); } - - if (pos >= max_length) { return; } - - // +1 for the terminating 0 char. - send_stdout_pipe_buffer(pos + 1); - } + out = get_stdout(&use_color); +#endif - } else { +#ifndef PX4_LOG_COLORIZED_OUTPUT + use_color = false; #endif - if (level >= _PX4_LOG_LEVEL_INFO) { - PX4_LOG_COLOR_START - PX4_LOG_COLOR_MESSAGE - va_list argptr; - va_start(argptr, fmt); - vprintf(fmt, argptr); - va_end(argptr); - PX4_LOG_COLOR_END - } + if (level >= _PX4_LOG_LEVEL_INFO) { + if (use_color) { fputs(__px4_log_level_color[level], out); } -#ifdef __PX4_POSIX - } + va_list argptr; + va_start(argptr, fmt); + vfprintf(out, fmt, argptr); + va_end(argptr); -#endif + if (use_color) { fputs(PX4_ANSI_COLOR_RESET, out); } + } } diff --git a/src/platforms/px4_log.h b/src/platforms/px4_log.h index 1e6e2208b29fb105a2b6f441ba11dc00de0d8325..f3e72b07823414b82a50f2d852c67a82a724e67d 100644 --- a/src/platforms/px4_log.h +++ b/src/platforms/px4_log.h @@ -196,24 +196,6 @@ __END_DECLS #endif /* __PX4_POSIX */ -#ifdef PX4_LOG_COLORIZED_OUTPUT -#include <unistd.h> -#define PX4_LOG_COLOR_START \ - int use_color = isatty(STDOUT_FILENO); \ - if (use_color) printf("%s", __px4_log_level_color[level]); -#define PX4_LOG_COLOR_MODULE \ - if (use_color) printf(PX4_ANSI_COLOR_GRAY); -#define PX4_LOG_COLOR_MESSAGE \ - if (use_color) printf("%s", __px4_log_level_color[level]); -#define PX4_LOG_COLOR_END \ - if (use_color) printf(PX4_ANSI_COLOR_RESET); -#else -#define PX4_LOG_COLOR_START -#define PX4_LOG_COLOR_MODULE -#define PX4_LOG_COLOR_MESSAGE -#define PX4_LOG_COLOR_END -#endif /* PX4_LOG_COLORIZED_OUTPUT */ - /**************************************************************************** * Output format macros * Use these to implement the code level macros below diff --git a/src/systemcmds/tests/test_hysteresis.cpp b/src/systemcmds/tests/test_hysteresis.cpp index 8569a17b45048aff632af9fb28ef4da6961703db..17d884694c410c0092f7cad6ad678782d9d7c30b 100644 --- a/src/systemcmds/tests/test_hysteresis.cpp +++ b/src/systemcmds/tests/test_hysteresis.cpp @@ -1,4 +1,5 @@ #include <unit_test.h> +#include <unistd.h> #include <systemlib/hysteresis/hysteresis.h> diff --git a/src/systemcmds/tests/test_microbench_hrt.cpp b/src/systemcmds/tests/test_microbench_hrt.cpp index c4a75ce5d6dbef404294be16a24ced8216e0addc..80d917280c63bfd91925728db2c6ba9dde72c650 100644 --- a/src/systemcmds/tests/test_microbench_hrt.cpp +++ b/src/systemcmds/tests/test_microbench_hrt.cpp @@ -35,6 +35,7 @@ #include <time.h> #include <stdlib.h> +#include <unistd.h> #include <drivers/drv_hrt.h> #include <perf/perf_counter.h> diff --git a/src/systemcmds/tests/test_microbench_math.cpp b/src/systemcmds/tests/test_microbench_math.cpp index 7e492a342be726aae2ab91989c4f24c28be24149..a3d50f5adf2cca9f1f78f79bcfcef20671d615b5 100644 --- a/src/systemcmds/tests/test_microbench_math.cpp +++ b/src/systemcmds/tests/test_microbench_math.cpp @@ -35,6 +35,7 @@ #include <time.h> #include <stdlib.h> +#include <unistd.h> #include <drivers/drv_hrt.h> #include <perf/perf_counter.h> diff --git a/src/systemcmds/tests/test_microbench_matrix.cpp b/src/systemcmds/tests/test_microbench_matrix.cpp index aac4f97858ba07d5cba605c1a2855de08d759836..2cd7107c77a47a0ecb616b22e93a860659867dcd 100644 --- a/src/systemcmds/tests/test_microbench_matrix.cpp +++ b/src/systemcmds/tests/test_microbench_matrix.cpp @@ -35,6 +35,7 @@ #include <time.h> #include <stdlib.h> +#include <unistd.h> #include <drivers/drv_hrt.h> #include <perf/perf_counter.h> diff --git a/src/systemcmds/tests/test_microbench_uorb.cpp b/src/systemcmds/tests/test_microbench_uorb.cpp index 85ead44fac98e5d8e6c9397f81b7e1f7942bcb67..9d9faff226fa7cc6507497ec83c976e1e3b71c60 100644 --- a/src/systemcmds/tests/test_microbench_uorb.cpp +++ b/src/systemcmds/tests/test_microbench_uorb.cpp @@ -35,6 +35,7 @@ #include <time.h> #include <stdlib.h> +#include <unistd.h> #include <drivers/drv_hrt.h> #include <perf/perf_counter.h> diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp index 0e1b270975f493a711725bd70e00d80aff21dad0..c389eb18b08d784b20b750e833b9bd31093ddeec 100644 --- a/src/systemcmds/tests/test_mixer.cpp +++ b/src/systemcmds/tests/test_mixer.cpp @@ -40,6 +40,7 @@ #include <limits> #include <dirent.h> #include <string.h> +#include <unistd.h> #include <px4_config.h> #include <mixer/mixer.h> diff --git a/src/systemcmds/tests/test_parameters.cpp b/src/systemcmds/tests/test_parameters.cpp index 2d2e9cb7e9dfecd03e5aee31521d906d2c943912..317309fc8d67bf9e9517b0b0fa2ff160420beb49 100644 --- a/src/systemcmds/tests/test_parameters.cpp +++ b/src/systemcmds/tests/test_parameters.cpp @@ -2,6 +2,7 @@ #include <px4_defines.h> #include <fcntl.h> +#include <unistd.h> class ParameterTest : public UnitTest {