aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-07-30 11:11:11 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-07-30 11:11:11 +0200
commit8e63dd57282bb76716fefbdd7c788cbf7797d1cc (patch)
tree8a83831f2d06af874e1b5b7d35f4abaddbd6460d /src/modules
parent0b12efc8400519724a2884e20bbb44d8caf7629d (diff)
parentd14891554e269714834360eb52242f8d66e1e6f9 (diff)
downloadpx4-firmware-8e63dd57282bb76716fefbdd7c788cbf7797d1cc.tar.gz
px4-firmware-8e63dd57282bb76716fefbdd7c788cbf7797d1cc.tar.bz2
px4-firmware-8e63dd57282bb76716fefbdd7c788cbf7797d1cc.zip
Merge branch 'master' of github.com:PX4/Firmware into vector_control
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.c17
-rw-r--r--src/modules/commander/commander.c12
-rw-r--r--src/modules/mavlink/mavlink.c47
-rw-r--r--src/modules/mavlink/mavlink_log.c11
-rw-r--r--src/modules/sensors/sensor_params.c2
-rw-r--r--src/modules/sensors/sensors.cpp83
-rw-r--r--src/modules/systemlib/airspeed.c4
-rw-r--r--src/modules/systemlib/module.mk3
-rw-r--r--src/modules/systemlib/system_params.c47
-rw-r--r--src/modules/uORB/topics/esc_status.h3
13 files changed, 152 insertions, 92 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..6a304896a 100644
--- a/src/modules/commander/accelerometer_calibration.c
+++ b/src/modules/commander/accelerometer_calibration.c
@@ -268,8 +268,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
float accel_disp[3] = { 0.0f, 0.0f, 0.0f };
/* EMA time constant in seconds*/
float ema_len = 0.2f;
- /* set "still" threshold to 0.1 m/s^2 */
- float still_thr2 = pow(0.1f, 2);
+ /* set "still" threshold to 0.25 m/s^2 */
+ float still_thr2 = pow(0.25f, 2);
/* set accel error threshold to 5m/s^2 */
float accel_err_thr = 5.0f;
/* still time required in us */
@@ -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/commander/commander.c b/src/modules/commander/commander.c
index 928d9b85e..e9d1f3954 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -282,7 +282,7 @@ void tune_error(void)
void do_rc_calibration(int status_pub, struct vehicle_status_s *status)
{
- if (current_status.offboard_control_signal_lost) {
+ if (current_status.rc_signal_lost) {
mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
return;
}
@@ -587,6 +587,8 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
close(fd);
+ int errcount = 0;
+
while (calibration_counter < calibration_count) {
/* wait blocking for new data */
@@ -602,8 +604,12 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
calibration_counter++;
} else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ errcount++;
+ }
+
+ if (errcount > 1000) {
+ /* any persisting poll error is a reason to abort */
+ mavlink_log_info(mavlink_fd, "permanent gyro error, aborted.");
return;
}
}
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/sensor_params.c b/src/modules/sensors/sensor_params.c
index 252c1b7a9..133cda8d6 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -68,7 +68,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
-PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667);
+PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 1667);
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index ae5a55109..7ff9e19b4 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -60,6 +60,7 @@
#include <drivers/drv_baro.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_adc.h>
+#include <drivers/drv_airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -139,14 +140,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 */
@@ -199,7 +198,7 @@ private:
float mag_scale[3];
float accel_offset[3];
float accel_scale[3];
- int diff_pres_offset_pa;
+ float diff_pres_offset_pa;
int rc_type;
@@ -232,6 +231,7 @@ private:
float battery_voltage_scaling;
int rc_rl1_DSM_VCC_control;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -282,6 +282,7 @@ private:
param_t battery_voltage_scaling;
param_t rc_rl1_DSM_VCC_control;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -393,13 +394,11 @@ namespace sensors
#endif
static const int ERROR = -1;
-Sensors *g_sensors;
+Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
-#ifdef CONFIG_HRT_PPM
_ppm_last_valid(0),
-#endif
_fd_adc(-1),
_last_adc(0),
@@ -558,25 +557,11 @@ Sensors::parameters_update()
/* rc values */
for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) {
- if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) {
- warnx("Failed getting min for chan %d", i);
- }
-
- if (param_get(_parameter_handles.trim[i], &(_parameters.trim[i])) != OK) {
- warnx("Failed getting trim for chan %d", i);
- }
-
- if (param_get(_parameter_handles.max[i], &(_parameters.max[i])) != OK) {
- warnx("Failed getting max for chan %d", i);
- }
-
- if (param_get(_parameter_handles.rev[i], &(_parameters.rev[i])) != OK) {
- warnx("Failed getting rev for chan %d", i);
- }
-
- if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) {
- warnx("Failed getting dead zone for chan %d", i);
- }
+ param_get(_parameter_handles.min[i], &(_parameters.min[i]));
+ param_get(_parameter_handles.trim[i], &(_parameters.trim[i]));
+ param_get(_parameter_handles.max[i], &(_parameters.max[i]));
+ param_get(_parameter_handles.rev[i], &(_parameters.rev[i]));
+ param_get(_parameter_handles.dz[i], &(_parameters.dz[i]));
_parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
@@ -666,21 +651,10 @@ Sensors::parameters_update()
warnx("Failed getting mode aux 5 index");
}
- if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) {
- warnx("Failed getting rc scaling for roll");
- }
-
- if (param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)) != OK) {
- warnx("Failed getting rc scaling for pitch");
- }
-
- if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) {
- warnx("Failed getting rc scaling for yaw");
- }
-
- if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) {
- warnx("Failed getting rc scaling for flaps");
- }
+ param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll));
+ param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch));
+ param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw));
+ param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps));
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -1045,6 +1019,20 @@ Sensors::parameter_update_poll(bool forced)
close(fd);
+ fd = open(AIRSPEED_DEVICE_PATH, 0);
+
+ /* this sensor is optional, abort without error */
+
+ if (fd > 0) {
+ struct airspeed_scale airscale = {
+ _parameters.diff_pres_offset_pa,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ }
+
#if 0
printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]);
printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]);
@@ -1135,16 +1123,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 +1322,6 @@ Sensors::ppm_poll()
}
}
-#endif
void
Sensors::task_main_trampoline(int argc, char *argv[])
@@ -1445,10 +1434,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 +1475,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/airspeed.c b/src/modules/systemlib/airspeed.c
index 15bb833a9..e01cc4dda 100644
--- a/src/modules/systemlib/airspeed.c
+++ b/src/modules/systemlib/airspeed.c
@@ -62,7 +62,7 @@ float calc_indicated_airspeed(float differential_pressure)
if (differential_pressure > 0) {
return sqrtf((2.0f*differential_pressure) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
} else {
- return -sqrtf((2.0f*fabs(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
+ return -sqrtf((2.0f*fabsf(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
}
}
@@ -106,6 +106,6 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp
return sqrtf((2.0f*(pressure_difference)) / density);
} else
{
- return -sqrtf((2.0f*fabs(pressure_difference)) / density);
+ return -sqrtf((2.0f*fabsf(pressure_difference)) / density);
}
}
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);
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h
index e67a39e1e..00cf59b28 100644
--- a/src/modules/uORB/topics/esc_status.h
+++ b/src/modules/uORB/topics/esc_status.h
@@ -63,7 +63,8 @@
enum ESC_VENDOR {
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
- ESC_VENDOR_MIKROKOPTER /**< Mikrokopter */
+ ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
+ ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
};
enum ESC_CONNECTION_TYPE {