aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/lib/version/version.h3
-rw-r--r--src/modules/sdlog2/logbuffer.c3
-rw-r--r--src/modules/sdlog2/sdlog2.c53
-rw-r--r--src/modules/uORB/topics/telemetry_status.h4
-rw-r--r--src/platforms/px4_config.h1
-rw-r--r--src/platforms/px4_defines.h6
6 files changed, 43 insertions, 27 deletions
diff --git a/src/lib/version/version.h b/src/lib/version/version.h
index b79fee182..f0071f3b5 100644
--- a/src/lib/version/version.h
+++ b/src/lib/version/version.h
@@ -59,4 +59,7 @@
#define HW_ARCH "PX4_STM32F4DISCOVERY"
#endif
+#ifdef CONFIG_ARCH_BOARD_LINUXTEST
+#define HW_ARCH "LINUXTEST"
+#endif
#endif /* VERSION_H_ */
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
index 2da67d8a9..9e25dd2f2 100644
--- a/src/modules/sdlog2/logbuffer.c
+++ b/src/modules/sdlog2/logbuffer.c
@@ -39,6 +39,7 @@
* @author Anton Babushkin <anton.babushkin@me.com>
*/
+#include <px4_defines.h>
#include <string.h>
#include <stdlib.h>
@@ -50,7 +51,7 @@ int logbuffer_init(struct logbuffer_s *lb, int size)
lb->write_ptr = 0;
lb->read_ptr = 0;
lb->data = malloc(lb->size);
- return (lb->data == 0) ? ERROR : OK;
+ return (lb->data == 0) ? PX4_ERROR : PX4_OK;
}
int logbuffer_count(struct logbuffer_s *lb)
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index d19c1942b..7cca4c6fa 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -43,6 +43,7 @@
*/
#include <px4_config.h>
+#include <px4_defines.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/prctl.h>
@@ -113,7 +114,7 @@
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
-#define PX4_EPOCH_SECS 1234567890ULL
+#define PX4_EPOCH_SECS 1234567890L
/**
* Logging rate.
@@ -292,7 +293,7 @@ sdlog2_usage(const char *reason)
fprintf(stderr, "%s\n", reason);
}
- errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t -x\n"
+ warnx("usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t -x\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
@@ -313,6 +314,7 @@ int sdlog2_main(int argc, char *argv[])
{
if (argc < 2) {
sdlog2_usage("missing command");
+ return 1;
}
if (!strcmp(argv[1], "start")) {
@@ -320,7 +322,7 @@ int sdlog2_main(int argc, char *argv[])
if (thread_running) {
warnx("already running");
/* this is not an error */
- exit(0);
+ return 0;
}
main_thread_should_exit = false;
@@ -330,7 +332,7 @@ int sdlog2_main(int argc, char *argv[])
3000,
sdlog2_thread_main,
(char * const *)argv);
- exit(0);
+ return 0;
}
if (!strcmp(argv[1], "stop")) {
@@ -339,7 +341,7 @@ int sdlog2_main(int argc, char *argv[])
}
main_thread_should_exit = true;
- exit(0);
+ return 0;
}
if (!thread_running) {
@@ -371,7 +373,7 @@ int sdlog2_main(int argc, char *argv[])
}
sdlog2_usage("unrecognized command");
- exit(1);
+ return 1;
}
int create_log_dir()
@@ -604,7 +606,8 @@ static void *logwriter_thread(void *arg)
if (n < 0) {
main_thread_should_exit = true;
- err(1, "error writing log file");
+ warn("error writing log file");
+ break;
}
if (n > 0) {
@@ -653,7 +656,7 @@ void sdlog2_start_log()
/* create log dir if needed */
if (create_log_dir() != 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
- exit(1);
+ return;
}
/* initialize statistics counter */
@@ -679,7 +682,7 @@ void sdlog2_start_log()
/* start log buffer emptying thread */
if (0 != pthread_create(&logwriter_pthread, &logwriter_attr, logwriter_thread, &lb)) {
- errx(1, "error creating logwriter thread");
+ warnx("error creating logwriter thread");
}
/* write all performance counters */
@@ -959,7 +962,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (check_free_space() != OK) {
- errx(1, "ERR: MicroSD almost full");
+ warnx("ERR: MicroSD almost full");
+ return 1;
}
@@ -967,7 +971,8 @@ int sdlog2_thread_main(int argc, char *argv[])
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret != 0 && errno != EEXIST) {
- err(1, "ERR: failed creating log dir: %s", log_root);
+ warn("ERR: failed creating log dir: %s", log_root);
+ return 1;
}
/* copy conversion scripts */
@@ -985,7 +990,8 @@ int sdlog2_thread_main(int argc, char *argv[])
warnx("log buffer size: %i bytes", log_buffer_size);
if (OK != logbuffer_init(&lb, log_buffer_size)) {
- errx(1, "can't allocate log buffer, exiting");
+ warnx("can't allocate log buffer, exiting");
+ return 1;
}
struct vehicle_status_s buf_status;
@@ -1615,8 +1621,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (buf.triplet.current.valid) {
log_msg.msg_type = LOG_GPSP_MSG;
log_msg.body.log_GPSP.nav_state = buf.triplet.nav_state;
- log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
- log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
+ log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * (double)1e7);
+ log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * (double)1e7);
log_msg.body.log_GPSP.alt = buf.triplet.current.alt;
log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw;
log_msg.body.log_GPSP.type = buf.triplet.current.type;
@@ -1904,7 +1910,7 @@ int file_copy(const char *file_old, const char *file_new)
if (source == NULL) {
warnx("ERR: open in");
- return 1;
+ return PX4_ERROR;
}
target = fopen(file_new, "w");
@@ -1912,7 +1918,7 @@ int file_copy(const char *file_old, const char *file_new)
if (target == NULL) {
fclose(source);
warnx("ERR: open out");
- return 1;
+ return PX4_ERROR;
}
char buf[128];
@@ -1923,7 +1929,7 @@ int file_copy(const char *file_old, const char *file_new)
if (ret <= 0) {
warnx("error writing file");
- ret = 1;
+ ret = PX4_ERROR;
break;
}
}
@@ -1933,7 +1939,7 @@ int file_copy(const char *file_old, const char *file_new)
fclose(source);
fclose(target);
- return OK;
+ return PX4_OK;
}
int check_free_space()
@@ -1941,19 +1947,20 @@ int check_free_space()
/* use statfs to determine the number of blocks left */
FAR struct statfs statfs_buf;
if (statfs(mountpoint, &statfs_buf) != OK) {
- errx(ERROR, "ERR: statfs");
+ warnx("ERR: statfs");
+ return PX4_ERROR;
}
/* use a threshold of 50 MiB */
- if (statfs_buf.f_bavail < (int)(50 * 1024 * 1024 / statfs_buf.f_bsize)) {
+ if (statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(50 * 1024 * 1024 / statfs_buf.f_bsize)) {
mavlink_and_console_log_critical(mavlink_fd,
"[sdlog2] no space on MicroSD: %u MiB",
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize) / (1024U * 1024U));
/* we do not need a flag to remember that we sent this warning because we will exit anyway */
- return ERROR;
+ return PX4_ERROR;
/* use a threshold of 100 MiB to send a warning */
- } else if (!space_warning_sent && statfs_buf.f_bavail < (int)(100 * 1024 * 1024 / statfs_buf.f_bsize)) {
+ } else if (!space_warning_sent && statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(100 * 1024 * 1024 / statfs_buf.f_bsize)) {
mavlink_and_console_log_critical(mavlink_fd,
"[sdlog2] space on MicroSD low: %u MiB",
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize) / (1024U * 1024U));
@@ -1961,7 +1968,7 @@ int check_free_space()
space_warning_sent = true;
}
- return OK;
+ return PX4_OK;
}
void handle_command(struct vehicle_command_s *cmd)
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 93193f32b..ee950f4db 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -93,8 +93,8 @@ static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_I
// included but telemetry_status_orb_id is not referenced. The inline works if you
// choose to use it, but you can continue to just directly index into the array as well.
// If you don't use the inline this ends up being a no-op with no additional code emitted.
-extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index);
-extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index)
+//static const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index);
+static inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index)
{
return telemetry_status_orb_id[index];
}
diff --git a/src/platforms/px4_config.h b/src/platforms/px4_config.h
index c53fd63d4..d2d1708eb 100644
--- a/src/platforms/px4_config.h
+++ b/src/platforms/px4_config.h
@@ -44,6 +44,7 @@
#include <px4_config.h>
#elif defined (__PX4_LINUX)
#define CONFIG_NFILE_STREAMS 1
+#define CONFIG_ARCH_BOARD_LINUXTEST 1
#define px4_errx(x, ...) errx(x, __VA_ARGS__)
diff --git a/src/platforms/px4_defines.h b/src/platforms/px4_defines.h
index 091d67e05..26c9a8595 100644
--- a/src/platforms/px4_defines.h
+++ b/src/platforms/px4_defines.h
@@ -69,7 +69,7 @@
#elif defined(__PX4_NUTTX) || defined(__PX4_LINUX)
/*
- * Building for NuttX
+ * Building for NuttX or Linux
*/
#include <platforms/px4_includes.h>
/* Main entry point */
@@ -102,6 +102,8 @@ typedef param_t px4_param_t;
#define _PX4_IOC(x,y) _IOC(x,y)
+#define px4_statfs_buf_f_bavail_t int
+
/* Linux Specific defines */
#elif defined(__PX4_LINUX)
@@ -123,6 +125,8 @@ __END_DECLS
#define USEC2TICK(x) (PX4_TICKS_PER_SEC*(long)x/1000000L)
+#define px4_statfs_buf_f_bavail_t unsigned long
+
#endif