aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-07-20 08:30:20 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-07-20 08:30:20 +0200
commitc88e8e335c08fc078913f22a5c546bd9e299eaf6 (patch)
treebc2c2337eb106d0c12c8dec9d1e102a1d7d1c790 /src/modules
parent39d88471896ac46c4aae475f7d6c73e44e7b5f25 (diff)
parenta8ac56b9e5eb8c1501ea592b4417aa8becd7236c (diff)
downloadpx4-firmware-c88e8e335c08fc078913f22a5c546bd9e299eaf6.tar.gz
px4-firmware-c88e8e335c08fc078913f22a5c546bd9e299eaf6.tar.bz2
px4-firmware-c88e8e335c08fc078913f22a5c546bd9e299eaf6.zip
Merged master
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp3
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp6
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp6
-rw-r--r--src/modules/commander/accelerometer_calibration.c13
-rw-r--r--src/modules/mavlink/mavlink.c47
-rw-r--r--src/modules/mavlink/mavlink_log.c11
-rw-r--r--src/modules/sensors/sensors.cpp19
-rw-r--r--src/modules/systemlib/module.mk3
-rw-r--r--src/modules/systemlib/system_params.c47
9 files changed, 108 insertions, 47 deletions
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 4befdc879..372b2d162 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -121,12 +121,13 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("is running\n");
+ exit(0);
} else {
warnx("not started\n");
+ exit(1);
}
- exit(0);
}
usage("unrecognized command");
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index d8b40ac3b..1eff60e88 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -139,10 +139,12 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tattitude_estimator_ekf app is running\n");
+ warnx("running");
+ exit(0);
} else {
- printf("\tattitude_estimator_ekf app not started\n");
+ warnx("not started");
+ exit(1);
}
exit(0);
diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
index 3ca50fb39..107c2dfb1 100755
--- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
@@ -139,10 +139,12 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tattitude_estimator_so3_comp app is running\n");
+ warnx("running");
+ exit(0);
} else {
- printf("\tattitude_estimator_so3_comp app not started\n");
+ warnx("not started");
+ exit(1);
}
exit(0);
diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c
index 48a36ac26..dc653a079 100644
--- a/src/modules/commander/accelerometer_calibration.c
+++ b/src/modules/commander/accelerometer_calibration.c
@@ -283,6 +283,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
hrt_abstime t = t_start;
hrt_abstime t_prev = t_start;
hrt_abstime t_still = 0;
+
+ unsigned poll_errcount = 0;
+
while (true) {
/* wait blocking for new data */
int poll_ret = poll(fds, 1, 1000);
@@ -327,12 +330,14 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
}
}
} else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "ERROR: poll failure");
- return -3;
+ poll_errcount++;
}
if (t > t_timeout) {
- mavlink_log_info(mavlink_fd, "ERROR: timeout");
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_info(mavlink_fd, "ERROR: failed reading accel");
return -1;
}
}
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 7c1c4b175..919d01561 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -420,12 +420,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
case 921600: speed = B921600; break;
default:
- fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
return -EINVAL;
}
/* open uart */
- printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
+ warnx("UART is %s, baudrate is %d\n", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -433,37 +433,35 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
int termios_state;
*is_usb = false;
- /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */
- if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) {
- /* Back up the original uart configuration to restore it after exit */
- if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
- close(uart);
- return -1;
- }
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
+ warnx("ERROR get termios config %s: %d\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+ /* Fill the struct for the new configuration */
+ tcgetattr(uart, &uart_config);
- /* Fill the struct for the new configuration */
- tcgetattr(uart, &uart_config);
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
- /* Clear ONLCR flag (which appends a CR for every LF) */
- uart_config.c_oflag &= ~ONLCR;
+ /* USB serial is indicated by /dev/ttyACM0*/
+ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) {
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
+ }
- if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
- close(uart);
- return -1;
- }
-
- } else {
- *is_usb = true;
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ close(uart);
+ return -1;
}
return uart;
@@ -751,8 +749,7 @@ int mavlink_thread_main(int argc, char *argv[])
pthread_join(uorb_receive_thread, NULL);
/* Reset the UART flags to original state */
- if (!usb_uart)
- tcsetattr(uart, TCSANOW, &uart_config_original);
+ tcsetattr(uart, TCSANOW, &uart_config_original);
thread_running = false;
diff --git a/src/modules/mavlink/mavlink_log.c b/src/modules/mavlink/mavlink_log.c
index d9416a08b..192195856 100644
--- a/src/modules/mavlink/mavlink_log.c
+++ b/src/modules/mavlink/mavlink_log.c
@@ -41,16 +41,20 @@
#include <string.h>
#include <stdlib.h>
+#include <stdio.h>
#include <stdarg.h>
#include <mavlink/mavlink_log.h>
+static FILE* text_recorder_fd = NULL;
+
void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
{
lb->size = size;
lb->start = 0;
lb->count = 0;
lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage));
+ text_recorder_fd = fopen("/fs/microsd/text_recorder.txt", "w");
}
int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
@@ -82,6 +86,13 @@ int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessa
memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage));
lb->start = (lb->start + 1) % lb->size;
--lb->count;
+
+ if (text_recorder_fd) {
+ fwrite(elem->text, 1, strnlen(elem->text, 50), text_recorder_fd);
+ fputc("\n", text_recorder_fd);
+ fsync(text_recorder_fd);
+ }
+
return 0;
} else {
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index ae5a55109..b2a6c6a79 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -139,14 +139,12 @@ public:
private:
static const unsigned _rc_max_chan_count = RC_CHANNELS_MAX; /**< maximum number of r/c channels we handle */
-#if CONFIG_HRT_PPM
hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */
/**
* Gather and publish PPM input data.
*/
void ppm_poll();
-#endif
/* XXX should not be here - should be own driver */
int _fd_adc; /**< ADC driver handle */
@@ -397,9 +395,7 @@ Sensors *g_sensors;
}
Sensors::Sensors() :
-#ifdef CONFIG_HRT_PPM
_ppm_last_valid(0),
-#endif
_fd_adc(-1),
_last_adc(0),
@@ -1135,16 +1131,18 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
-#if CONFIG_HRT_PPM
void
Sensors::ppm_poll()
{
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
- bool rc_updated;
- orb_check(_rc_sub, &rc_updated);
+ struct pollfd fds[1];
+ fds[0].fd = _rc_sub;
+ fds[0].events = POLLIN;
+ /* check non-blocking for new data */
+ int poll_ret = poll(fds, 1, 0);
- if (rc_updated) {
+ if (poll_ret > 0) {
struct rc_input_values rc_input;
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
@@ -1332,7 +1330,6 @@ Sensors::ppm_poll()
}
}
-#endif
void
Sensors::task_main_trampoline(int argc, char *argv[])
@@ -1445,10 +1442,8 @@ Sensors::task_main()
if (_publishing)
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
-#ifdef CONFIG_HRT_PPM
/* Look for new r/c input data */
ppm_poll();
-#endif
perf_end(_loop_perf);
}
@@ -1488,7 +1483,7 @@ int sensors_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (sensors::g_sensors != nullptr)
- errx(1, "sensors task already running");
+ errx(0, "sensors task already running");
sensors::g_sensors = new Sensors;
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index fd0289c9a..b470c1227 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -47,4 +47,5 @@ SRCS = err.c \
pid/pid.c \
geo/geo.c \
systemlib.c \
- airspeed.c
+ airspeed.c \
+ system_params.c
diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c
new file mode 100644
index 000000000..75be090f8
--- /dev/null
+++ b/src/modules/systemlib/system_params.c
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file system_params.c
+ *
+ * System wide parameters
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+// Auto-start script with index #n
+PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
+
+// Automatically configure default values
+PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);