aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_init.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_internal.h2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_led.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_pwm_servo.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_spi.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_usb.c2
-rw-r--r--src/drivers/boards/px4io/px4io_init.c2
-rw-r--r--src/drivers/boards/px4io/px4io_internal.h2
-rw-r--r--src/drivers/boards/px4io/px4io_pwm_servo.c2
-rw-r--r--src/drivers/drv_gpio.h6
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp160
-rw-r--r--src/drivers/gps/ubx.cpp2
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hott_telemetry/hott_telemetry_main.c134
-rw-r--r--src/drivers/hott_telemetry/messages.c171
-rw-r--r--src/drivers/hott_telemetry/messages.h122
-rw-r--r--src/drivers/md25/md25_main.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp127
-rw-r--r--src/drivers/px4fmu/fmu.cpp2
-rw-r--r--src/drivers/px4io/px4io.cpp92
-rw-r--r--src/drivers/px4io/uploader.cpp9
-rw-r--r--src/drivers/stm32/adc/adc.cpp2
-rw-r--r--src/drivers/stm32/drv_hrt.c6
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c2
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp2
26 files changed, 612 insertions, 249 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index aeaf830de..735bdb41a 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[])
}
thread_should_exit = false;
- ardrone_interface_task = task_spawn("ardrone_interface",
+ ardrone_interface_task = task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
2048,
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c
index 69edc23ab..212a92cfa 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu/px4fmu_init.c
@@ -58,7 +58,7 @@
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu/px4fmu_internal.h
index 671a58f8f..383a046ff 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu/px4fmu_internal.h
@@ -50,7 +50,7 @@
__BEGIN_DECLS
/* these headers are not C++ safe */
-#include <stm32_internal.h>
+#include <stm32.h>
/****************************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu/px4fmu_led.c
index 34fd194c3..31b25984e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu/px4fmu_led.c
@@ -41,7 +41,7 @@
#include <stdbool.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
index cb8918306..d85131dd8 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu/px4fmu_spi.c
index b5d00eac0..e05ddecf3 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu/px4fmu_spi.c
@@ -52,7 +52,7 @@
#include "up_arch.h"
#include "chip.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu/px4fmu_usb.c
index b0b669fbe..0be981c1e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu/px4fmu_usb.c
@@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io/px4io_init.c
index d36353c6f..15c59e423 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io/px4io_init.c
@@ -54,7 +54,7 @@
#include <nuttx/arch.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4io_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io/px4io_internal.h
index eb2820bb7..6638e715e 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io/px4io_internal.h
@@ -47,7 +47,7 @@
#include <nuttx/compiler.h>
#include <stdint.h>
-#include <stm32_internal.h>
+#include <stm32.h>
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io/px4io_pwm_servo.c
index a2f73c429..6df470da6 100644
--- a/src/drivers/boards/px4io/px4io_pwm_servo.c
+++ b/src/drivers/boards/px4io/px4io_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index 92d184326..7e3998fca 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 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
@@ -42,7 +42,7 @@
#include <sys/ioctl.h>
-#ifdef CONFIG_ARCH_BOARD_PX4FMU
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/*
* PX4FMU GPIO numbers.
*
@@ -67,7 +67,7 @@
#endif
-#ifdef CONFIG_ARCH_BOARD_PX4IO
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
/*
* PX4IO GPIO numbers.
*
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index e50395e47..b34d3fa5d 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -37,7 +37,7 @@
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -77,15 +77,16 @@
#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
/* I2C bus address */
-#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
+#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
/* Register address */
-#define READ_CMD 0x07 /* Read the data */
-
+#define READ_CMD 0x07 /* Read the data */
+
/**
- * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * You can set this value to 12 if you want a zero reading below 15km/h.
*/
-#define MIN_ACCURATE_DIFF_PRES_PA 12
+#define MIN_ACCURATE_DIFF_PRES_PA 0
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@@ -105,38 +106,38 @@ class ETSAirspeed : public device::I2C
public:
ETSAirspeed(int bus, int address = I2C_ADDRESS);
virtual ~ETSAirspeed();
-
- virtual int init();
-
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
/**
* Diagnostics - print some basic information about the driver.
*/
- void print_info();
-
+ void print_info();
+
protected:
- virtual int probe();
+ virtual int probe();
private:
- work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- differential_pressure_s *_reports;
- bool _sensor_ok;
- int _measure_ticks;
- bool _collect_phase;
- int _diff_pres_offset;
-
- orb_advert_t _airspeed_pub;
-
- perf_counter_t _sample_perf;
- perf_counter_t _comms_errors;
- perf_counter_t _buffer_overflows;
-
-
+ work_s _work;
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ differential_pressure_s *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _diff_pres_offset;
+
+ orb_advert_t _airspeed_pub;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -144,28 +145,28 @@ private:
* @param address The I2C bus address to probe.
* @return True if the device is present.
*/
- int probe_address(uint8_t address);
-
+ int probe_address(uint8_t address);
+
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
- void start();
-
+ void start();
+
/**
* Stop the automatic measurement state machine.
*/
- void stop();
-
+ void stop();
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
- void cycle();
- int measure();
- int collect();
+ void cycle();
+ int measure();
+ int collect();
/**
* Static trampoline from the workq context; because we don't have a
@@ -173,9 +174,9 @@ private:
*
* @param arg Instance pointer for the driver that is polling.
*/
- static void cycle_trampoline(void *arg);
-
-
+ static void cycle_trampoline(void *arg);
+
+
};
/* helper macro for handling report buffer indices */
@@ -203,7 +204,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) :
{
// enable debug() calls
_debug_enabled = true;
-
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -230,6 +231,7 @@ ETSAirspeed::init()
/* allocate basic report buffers */
_num_reports = 2;
_reports = new struct differential_pressure_s[_num_reports];
+
for (unsigned i = 0; i < _num_reports; i++)
_reports[i].max_differential_pressure_pa = 0;
@@ -351,11 +353,11 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCGQUEUEDEPTH:
return _num_reports - 1;
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -432,14 +434,14 @@ ETSAirspeed::measure()
uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -447,30 +449,31 @@ int
ETSAirspeed::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
uint8_t val[2] = {0, 0};
-
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 2);
-
+
if (ret < 0) {
log("error reading from sensor: %d", ret);
return ret;
}
-
+
uint16_t diff_pres_pa = val[1] << 8 | val[0];
+ // XXX move the parameter read out of the driver.
param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
-
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+ if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
+
} else {
- diff_pres_pa -= _diff_pres_offset;
+ diff_pres_pa -= _diff_pres_offset;
}
- // XXX we may want to smooth out the readings to remove noise.
+ // XXX we may want to smooth out the readings to remove noise.
_reports[_next_report].timestamp = hrt_absolute_time();
_reports[_next_report].differential_pressure_pa = diff_pres_pa;
@@ -498,7 +501,7 @@ ETSAirspeed::collect()
ret = OK;
perf_end(_sample_perf);
-
+
return ret;
}
@@ -511,17 +514,19 @@ ETSAirspeed::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_DIFFPRESSURE};
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -653,8 +658,7 @@ start(int i2c_bus)
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -668,15 +672,14 @@ fail:
void
stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -773,10 +776,10 @@ info()
} // namespace
-static void
-ets_airspeed_usage()
+static void
+ets_airspeed_usage()
{
- fprintf(stderr, "usage: ets_airspeed [options] command\n");
+ fprintf(stderr, "usage: ets_airspeed command [options]\n");
fprintf(stderr, "options:\n");
fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT);
fprintf(stderr, "command:\n");
@@ -789,6 +792,7 @@ ets_airspeed_main(int argc, char *argv[])
int i2c_bus = PX4_I2C_BUS_DEFAULT;
int i;
+
for (i = 1; i < argc; i++) {
if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
if (argc > i + 1) {
@@ -802,12 +806,12 @@ ets_airspeed_main(int argc, char *argv[])
*/
if (!strcmp(argv[1], "start"))
ets_airspeed::start(i2c_bus);
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- ets_airspeed::stop();
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ ets_airspeed::stop();
/*
* Test the driver/device.
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index b3093b0f6..f2e7ca67d 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -739,7 +739,7 @@ UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
msg.msg_class = msg_class;
msg.msg_id = msg_id;
msg.rate = rate;
- send_message(CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
+ send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
}
void
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index d9aa772d4..bd027ce0b 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -224,7 +224,7 @@ HIL::init()
// gpio_reset();
/* start the HIL interface task */
- _task = task_spawn("fmuhil",
+ _task = task_spawn_cmd("fmuhil",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c
index a13a6ef58..4699ce5bf 100644
--- a/src/drivers/hott_telemetry/hott_telemetry_main.c
+++ b/src/drivers/hott_telemetry/hott_telemetry_main.c
@@ -53,6 +53,7 @@
#include <termios.h>
#include <sys/ioctl.h>
#include <unistd.h>
+#include <systemlib/err.h>
#include <systemlib/systemlib.h>
#include "messages.h"
@@ -60,56 +61,44 @@
static int thread_should_exit = false; /**< Deamon exit flag */
static int thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
-static char *daemon_name = "hott_telemetry";
-static char *commandline_usage = "usage: hott_telemetry start|status|stop [-d <device>]";
+static const char daemon_name[] = "hott_telemetry";
+static const char commandline_usage[] = "usage: hott_telemetry start|status|stop [-d <device>]";
-
-/* A little console messaging experiment - console helper macro */
-#define FATAL_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg); exit(1);
-#define ERROR_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg);
-#define INFO_MSG(_msg) printf("[%s] %s\n", daemon_name, _msg);
/**
* Deamon management function.
*/
__EXPORT int hott_telemetry_main(int argc, char *argv[]);
/**
- * Mainloop of deamon.
+ * Mainloop of daemon.
*/
int hott_telemetry_thread_main(int argc, char *argv[]);
-static int read_data(int uart, int *id);
-static int send_data(int uart, uint8_t *buffer, int size);
+static int recv_req_id(int uart, uint8_t *id);
+static int send_data(int uart, uint8_t *buffer, size_t size);
-static int open_uart(const char *device, struct termios *uart_config_original)
+static int
+open_uart(const char *device, struct termios *uart_config_original)
{
/* baud rate */
- int speed = B19200;
- int uart;
+ static const speed_t speed = B19200;
/* open uart */
- uart = open(device, O_RDWR | O_NOCTTY);
+ const int uart = open(device, O_RDWR | O_NOCTTY);
if (uart < 0) {
- char msg[80];
- sprintf(msg, "Error opening port: %s\n", device);
- FATAL_MSG(msg);
+ err(1, "Error opening port: %s", device);
}
-
- /* Try to set baud rate */
- struct termios uart_config;
+
+ /* Back up the original uart configuration to restore it after exit */
int termios_state;
-
- /* Back up the original uart configuration to restore it after exit */
- char msg[80];
-
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- sprintf(msg, "Error getting baudrate / termios config for %s: %d\n", device, termios_state);
close(uart);
- FATAL_MSG(msg);
+ err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state);
}
/* Fill the struct for the new configuration */
+ struct termios uart_config;
tcgetattr(uart, &uart_config);
/* Clear ONLCR flag (which appends a CR for every LF) */
@@ -117,16 +106,14 @@ static int open_uart(const char *device, struct termios *uart_config_original)
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- sprintf(msg, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n",
- device, termios_state);
close(uart);
- FATAL_MSG(msg);
+ err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)",
+ device, termios_state);
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- sprintf(msg, "Error setting baudrate / termios config for %s (tcsetattr)\n", device);
close(uart);
- FATAL_MSG(msg);
+ err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device);
}
/* Activate single wire mode */
@@ -135,39 +122,41 @@ static int open_uart(const char *device, struct termios *uart_config_original)
return uart;
}
-int read_data(int uart, int *id)
+int
+recv_req_id(int uart, uint8_t *id)
{
- const int timeout = 1000;
+ static const int timeout_ms = 1000; // TODO make it a define
struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
- char mode;
+ uint8_t mode;
- if (poll(fds, 1, timeout) > 0) {
+ if (poll(fds, 1, timeout_ms) > 0) {
/* Get the mode: binary or text */
- read(uart, &mode, 1);
- /* Read the device ID being polled */
- read(uart, id, 1);
+ read(uart, &mode, sizeof(mode));
/* if we have a binary mode request */
if (mode != BINARY_MODE_REQUEST_ID) {
return ERROR;
}
+ /* Read the device ID being polled */
+ read(uart, id, sizeof(*id));
} else {
- ERROR_MSG("UART timeout on TX/RX port");
+ warnx("UART timeout on TX/RX port");
return ERROR;
}
return OK;
}
-int send_data(int uart, uint8_t *buffer, int size)
+int
+send_data(int uart, uint8_t *buffer, size_t size)
{
usleep(POST_READ_DELAY_IN_USECS);
uint16_t checksum = 0;
- for (int i = 0; i < size; i++) {
+ for (size_t i = 0; i < size; i++) {
if (i == size - 1) {
/* Set the checksum: the first uint8_t is taken as the checksum. */
buffer[i] = checksum & 0xff;
@@ -176,7 +165,7 @@ int send_data(int uart, uint8_t *buffer, int size)
checksum += buffer[i];
}
- write(uart, &buffer[i], 1);
+ write(uart, &buffer[i], sizeof(buffer[i]));
/* Sleep before sending the next byte. */
usleep(POST_WRITE_DELAY_IN_USECS);
@@ -190,13 +179,14 @@ int send_data(int uart, uint8_t *buffer, int size)
return OK;
}
-int hott_telemetry_thread_main(int argc, char *argv[])
+int
+hott_telemetry_thread_main(int argc, char *argv[])
{
- INFO_MSG("starting");
+ warnx("starting");
thread_running = true;
- char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */
+ const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */
/* read commandline arguments */
for (int i = 0; i < argc && argv[i]; i++) {
@@ -206,45 +196,55 @@ int hott_telemetry_thread_main(int argc, char *argv[])
} else {
thread_running = false;
- ERROR_MSG("missing parameter to -d");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "missing parameter to -d\n%s", commandline_usage);
}
}
}
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
struct termios uart_config_original;
- int uart = open_uart(device, &uart_config_original);
+ const int uart = open_uart(device, &uart_config_original);
if (uart < 0) {
- ERROR_MSG("Failed opening HoTT UART, exiting.");
+ errx(1, "Failed opening HoTT UART, exiting.");
thread_running = false;
- exit(ERROR);
}
messages_init();
uint8_t buffer[MESSAGE_BUFFER_SIZE];
- int size = 0;
- int id = 0;
+ size_t size = 0;
+ uint8_t id = 0;
+ bool connected = true;
while (!thread_should_exit) {
- if (read_data(uart, &id) == OK) {
+ if (recv_req_id(uart, &id) == OK) {
+ if (!connected) {
+ connected = true;
+ warnx("OK");
+ }
+
switch (id) {
- case ELECTRIC_AIR_MODULE:
+ case EAM_SENSOR_ID:
build_eam_response(buffer, &size);
break;
+ case GPS_SENSOR_ID:
+ build_gps_response(buffer, &size);
+ break;
+
default:
continue; // Not a module we support.
}
send_data(uart, buffer, size);
+ } else {
+ connected = false;
+ warnx("syncing");
}
}
- INFO_MSG("exiting");
+ warnx("exiting");
close(uart);
@@ -256,23 +256,22 @@ int hott_telemetry_thread_main(int argc, char *argv[])
/**
* Process command line arguments and tart the daemon.
*/
-int hott_telemetry_main(int argc, char *argv[])
+int
+hott_telemetry_main(int argc, char *argv[])
{
if (argc < 1) {
- ERROR_MSG("missing command");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "missing command\n%s", commandline_usage);
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- INFO_MSG("deamon already running");
+ warnx("deamon already running");
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn("hott_telemetry",
+ deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
2048,
@@ -288,19 +287,14 @@ int hott_telemetry_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- INFO_MSG("daemon is running");
+ warnx("daemon is running");
} else {
- INFO_MSG("daemon not started");
+ warnx("daemon not started");
}
exit(0);
}
- ERROR_MSG("unrecognized command");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "unrecognized command\n%s", commandline_usage);
}
-
-
-
diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c
index f0f32d244..0ce56acef 100644
--- a/src/drivers/hott_telemetry/messages.c
+++ b/src/drivers/hott_telemetry/messages.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Simon Wilks <sjwilks@gmail.com>
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Simon Wilks <sjwilks@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,30 +34,47 @@
/**
* @file messages.c
- * @author Simon Wilks <sjwilks@gmail.com>
+ *
*/
#include "messages.h"
+#include <math.h>
+#include <stdio.h>
#include <string.h>
-#include <systemlib/systemlib.h>
+#include <systemlib/geo/geo.h>
#include <unistd.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
+#include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_gps_position.h>
+
+/* The board is very roughly 5 deg warmer than the surrounding air */
+#define BOARD_TEMP_OFFSET_DEG 5
-static int airspeed_sub = -1;
static int battery_sub = -1;
+static int gps_sub = -1;
+static int home_sub = -1;
static int sensor_sub = -1;
+static int airspeed_sub = -1;
+
+static bool home_position_set = false;
+static double home_lat = 0.0d;
+static double home_lon = 0.0d;
-void messages_init(void)
+void
+messages_init(void)
{
battery_sub = orb_subscribe(ORB_ID(battery_status));
+ gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ home_sub = orb_subscribe(ORB_ID(home_position));
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
airspeed_sub = orb_subscribe(ORB_ID(airspeed));
}
-void build_eam_response(uint8_t *buffer, int *size)
+void
+build_eam_response(uint8_t *buffer, size_t *size)
{
/* get a local copy of the current sensor values */
struct sensor_combined_s raw;
@@ -74,26 +91,154 @@ void build_eam_response(uint8_t *buffer, int *size)
memset(&msg, 0, *size);
msg.start = START_BYTE;
- msg.eam_sensor_id = ELECTRIC_AIR_MODULE;
- msg.sensor_id = EAM_SENSOR_ID;
+ msg.eam_sensor_id = EAM_SENSOR_ID;
+ msg.sensor_id = EAM_SENSOR_TEXT_ID;
+
msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20);
- msg.temperature2 = TEMP_ZERO_CELSIUS;
+ msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG;
+
msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10);
uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500);
msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
- /* get a local copy of the current sensor values */
+ /* get a local copy of the airspeed data */
struct airspeed_s airspeed;
memset(&airspeed, 0, sizeof(airspeed));
orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
- uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6);
+ uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f);
msg.speed_L = (uint8_t)speed & 0xff;
msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
+
msg.stop = STOP_BYTE;
+ memcpy(buffer, &msg, *size);
+}
+
+void
+build_gps_response(uint8_t *buffer, size_t *size)
+{
+ /* get a local copy of the current sensor values */
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+ orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
+
+ /* get a local copy of the battery data */
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
+ orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps);
+
+ struct gps_module_msg msg = { 0 };
+ *size = sizeof(msg);
+ memset(&msg, 0, *size);
+
+ msg.start = START_BYTE;
+ msg.sensor_id = GPS_SENSOR_ID;
+ msg.sensor_text_id = GPS_SENSOR_TEXT_ID;
+ msg.gps_num_sat = gps.satellites_visible;
+
+ /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */
+ msg.gps_fix_char = (uint8_t)(gps.fix_type + 48);
+ msg.gps_fix = (uint8_t)(gps.fix_type + 48);
+
+ /* No point collecting more data if we don't have a 3D fix yet */
+ if (gps.fix_type > 2) {
+ /* Current flight direction */
+ msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F);
+
+ /* GPS speed */
+ uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6);
+ msg.gps_speed_L = (uint8_t)speed & 0xff;
+ msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff;
+
+ /* Get latitude in degrees, minutes and seconds */
+ double lat = ((double)(gps.lat))*1e-7d;
+
+ /* Set the N or S specifier */
+ msg.latitude_ns = 0;
+ if (lat < 0) {
+ msg.latitude_ns = 1;
+ lat = abs(lat);
+ }
+
+ int deg;
+ int min;
+ int sec;
+ convert_to_degrees_minutes_seconds(lat, &deg, &min, &sec);
+
+ uint16_t lat_min = (uint16_t)(deg * 100 + min);
+ msg.latitude_min_L = (uint8_t)lat_min & 0xff;
+ msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff;
+ uint16_t lat_sec = (uint16_t)(sec);
+ msg.latitude_sec_L = (uint8_t)lat_sec & 0xff;
+ msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff;
+
+ /* Get longitude in degrees, minutes and seconds */
+ double lon = ((double)(gps.lon))*1e-7d;
+
+ /* Set the E or W specifier */
+ msg.longitude_ew = 0;
+ if (lon < 0) {
+ msg.longitude_ew = 1;
+ lon = abs(lon);
+ }
+
+ convert_to_degrees_minutes_seconds(lon, &deg, &min, &sec);
+
+ uint16_t lon_min = (uint16_t)(deg * 100 + min);
+ msg.longitude_min_L = (uint8_t)lon_min & 0xff;
+ msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff;
+ uint16_t lon_sec = (uint16_t)(sec);
+ msg.longitude_sec_L = (uint8_t)lon_sec & 0xff;
+ msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff;
+
+ /* Altitude */
+ uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f);
+ msg.altitude_L = (uint8_t)alt & 0xff;
+ msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
+
+ /* Get any (and probably only ever one) home_sub postion report */
+ bool updated;
+ orb_check(home_sub, &updated);
+ if (updated) {
+ /* get a local copy of the home position data */
+ struct home_position_s home;
+ memset(&home, 0, sizeof(home));
+ orb_copy(ORB_ID(home_position), home_sub, &home);
+
+ home_lat = ((double)(home.lat))*1e-7d;
+ home_lon = ((double)(home.lon))*1e-7d;
+ home_position_set = true;
+ }
+
+ /* Distance from home */
+ if (home_position_set) {
+ uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon);
+
+ msg.distance_L = (uint8_t)dist & 0xff;
+ msg.distance_H = (uint8_t)(dist >> 8) & 0xff;
+
+ /* Direction back to home */
+ uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F);
+ msg.home_direction = (uint8_t)bearing >> 1;
+ }
+ }
+
+ msg.stop = STOP_BYTE;
memcpy(buffer, &msg, *size);
-} \ No newline at end of file
+}
+
+void
+convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec)
+{
+ *deg = (int)val;
+
+ double delta = val - *deg;
+ const double min_d = delta * 60.0d;
+ *min = (int)min_d;
+ delta = min_d - *min;
+ *sec = (int)(delta * 10000.0d);
+}
diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h
index dd38075fa..e6d5cc723 100644
--- a/src/drivers/hott_telemetry/messages.h
+++ b/src/drivers/hott_telemetry/messages.h
@@ -44,11 +44,6 @@
#include <stdlib.h>
-/* The buffer size used to store messages. This must be at least as big as the number of
- * fields in the largest message struct.
- */
-#define MESSAGE_BUFFER_SIZE 50
-
/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request.
* Note that the value specified here is lower than 5000 (5ms) as time is lost constucting
* the message after the read which takes some milliseconds.
@@ -66,18 +61,18 @@
#define TEMP_ZERO_CELSIUS 0x14
/* Electric Air Module (EAM) constants. */
-#define ELECTRIC_AIR_MODULE 0x8e
-#define EAM_SENSOR_ID 0xe0
+#define EAM_SENSOR_ID 0x8e
+#define EAM_SENSOR_TEXT_ID 0xe0
/* The Electric Air Module message. */
struct eam_module_msg {
- uint8_t start; /**< Start byte */
- uint8_t eam_sensor_id; /**< EAM sensor ID */
+ uint8_t start; /**< Start byte */
+ uint8_t eam_sensor_id; /**< EAM sensor */
uint8_t warning;
- uint8_t sensor_id; /**< Sensor ID, why different? */
+ uint8_t sensor_id; /**< Sensor ID, why different? */
uint8_t alarm_inverse1;
uint8_t alarm_inverse2;
- uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
+ uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
uint8_t cell2_L;
uint8_t cell3_L;
uint8_t cell4_L;
@@ -95,30 +90,107 @@ struct eam_module_msg {
uint8_t batt1_voltage_H;
uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */
uint8_t batt2_voltage_H;
- uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
+ uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
uint8_t temperature2;
- uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
+ uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
uint8_t altitude_H;
- uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
+ uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
uint8_t current_H;
- uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
+ uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
uint8_t main_voltage_H;
- uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */
+ uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */
uint8_t battery_capacity_H;
- uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
+ uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
uint8_t climbrate_H;
- uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
- uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
+ uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
+ uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
uint8_t rpm_H;
- uint8_t electric_min; /**< Flight time in minutes. */
- uint8_t electric_sec; /**< Flight time in seconds. */
- uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
+ uint8_t electric_min; /**< Flight time in minutes. */
+ uint8_t electric_sec; /**< Flight time in seconds. */
+ uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
uint8_t speed_H;
- uint8_t stop; /**< Stop byte */
- uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
+ uint8_t stop; /**< Stop byte */
+ uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
};
+/**
+ * The maximum buffer size required to store a HoTT message.
+ */
+#define MESSAGE_BUFFER_SIZE sizeof(union { \
+ struct eam_module_msg eam; \
+})
+
+/* GPS sensor constants. */
+#define GPS_SENSOR_ID 0x8A
+#define GPS_SENSOR_TEXT_ID 0xA0
+
+/**
+ * The GPS sensor message
+ * Struct based on: https://code.google.com/p/diy-hott-gps/downloads
+ */
+struct gps_module_msg {
+ uint8_t start; /**< Start byte */
+ uint8_t sensor_id; /**< GPS sensor ID*/
+ uint8_t warning; /**< Byte 3: 0…= warning beeps */
+ uint8_t sensor_text_id; /**< GPS Sensor text mode ID */
+ uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */
+ uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */
+ uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */
+ uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */
+ uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */
+
+ uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */
+ uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */
+ uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */
+ uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */
+ uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */
+
+ uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */
+ uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */
+ uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */
+ uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/
+ uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */
+
+ uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */
+ uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */
+ uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */
+ uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */
+ uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */
+ uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */
+ uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */
+ uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */
+ uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */
+ uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */
+ uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */
+ uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */
+ uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */
+ uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */
+ uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */
+ uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */
+ uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */
+ uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */
+ uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */
+ uint8_t vibration; /**< Byte 39: vibration (1 bytes) */
+ uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */
+ uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */
+ uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */
+ uint8_t version; /**< Byte 43: 00 version number */
+ uint8_t stop; /**< Byte 44: 0x7D Ende byte */
+ uint8_t checksum; /**< Byte 45: Parity Byte */
+};
+
+/**
+ * The maximum buffer size required to store a HoTT message.
+ */
+#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \
+ struct gps_module_msg gps; \
+})
+
void messages_init(void);
-void build_eam_response(uint8_t *buffer, int *size);
+void build_eam_response(uint8_t *buffer, size_t *size);
+void build_gps_response(uint8_t *buffer, size_t *size);
+float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
+
#endif /* MESSAGES_H_ */
diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp
index 80850e708..e62c46b0d 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("md25",
+ deamon_task = task_spawn_cmd("md25",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
2048,
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index c67276f8a..e78d96569 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -74,6 +74,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/esc_status.h>
#include <systemlib/err.h>
@@ -87,7 +88,7 @@
#define MOTOR_STATE_PRESENT_MASK 0x80
#define MOTOR_STATE_ERROR_MASK 0x7F
#define MOTOR_SPINUP_COUNTER 2500
-
+#define ESC_UORB_PUBLISH_DELAY 200
class MK : public device::I2C
{
@@ -119,6 +120,7 @@ public:
int set_pwm_rate(unsigned rate);
int set_motor_count(unsigned count);
int set_motor_test(bool motortest);
+ int set_overrideSecurityChecks(bool overrideSecurityChecks);
int set_px4mode(int px4mode);
int set_frametype(int frametype);
unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput);
@@ -136,11 +138,15 @@ private:
unsigned int _motor;
int _px4mode;
int _frametype;
+
orb_advert_t _t_outputs;
orb_advert_t _t_actuators_effective;
+ orb_advert_t _t_esc_status;
+
unsigned int _num_outputs;
bool _primary_pwm_device;
bool _motortest;
+ bool _overrideSecurityChecks;
volatile bool _task_should_exit;
bool _armed;
@@ -214,6 +220,7 @@ struct MotorData_t {
unsigned int Version; // the version of the BL (0 = old)
unsigned int SetPoint; // written by attitude controller
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
unsigned int ReadMode; // select data to read
unsigned short RawPwmValue; // length of PWM pulse
@@ -243,8 +250,10 @@ MK::MK(int bus) :
_t_armed(-1),
_t_outputs(0),
_t_actuators_effective(0),
+ _t_esc_status(0),
_num_outputs(0),
_motortest(false),
+ _overrideSecurityChecks(false),
_motor(-1),
_px4mode(MAPPING_MK),
_frametype(FRAME_PLUS),
@@ -313,7 +322,7 @@ MK::init(unsigned motors)
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("mkblctrl",
+ _task = task_spawn_cmd("mkblctrl",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
@@ -464,6 +473,13 @@ MK::set_motor_test(bool motortest)
return OK;
}
+int
+MK::set_overrideSecurityChecks(bool overrideSecurityChecks)
+{
+ _overrideSecurityChecks = overrideSecurityChecks;
+ return OK;
+}
+
short
MK::scaling(float val, float inMin, float inMax, float outMin, float outMax)
{
@@ -506,8 +522,6 @@ MK::task_main()
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
&outputs);
-
-
/* advertise the effective control inputs */
actuator_controls_effective_s controls_effective;
memset(&controls_effective, 0, sizeof(controls_effective));
@@ -515,6 +529,12 @@ MK::task_main()
_t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1),
&controls_effective);
+ /* advertise the blctrl status */
+ esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+ _t_esc_status = orb_advertise(ORB_ID(esc_status), &esc);
+
+
pollfd fds[2];
fds[0].fd = _t_actuators;
@@ -602,9 +622,11 @@ MK::task_main()
}
}
- /* don't go under BLCTRL_MIN_VALUE */
- if (outputs.output[i] < BLCTRL_MIN_VALUE) {
- outputs.output[i] = BLCTRL_MIN_VALUE;
+ if(!_overrideSecurityChecks) {
+ /* don't go under BLCTRL_MIN_VALUE */
+ if (outputs.output[i] < BLCTRL_MIN_VALUE) {
+ outputs.output[i] = BLCTRL_MIN_VALUE;
+ }
}
/* output to BLCtrl's */
@@ -612,7 +634,10 @@ MK::task_main()
mk_servo_test(i);
} else {
- mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ //mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ // 11 Bit
+ Motor[i].SetPoint_PX4 = outputs.output[i];
+ mk_servo_set(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 2047)); // scale the output to 0 - 2047 and sent to output routine
}
}
@@ -635,8 +660,43 @@ MK::task_main()
}
+
+ /*
+ * Only update esc topic every half second.
+ */
+
+ if (hrt_absolute_time() - esc.timestamp > 500000) {
+ esc.counter++;
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = (uint8_t) _num_outputs;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_I2C;
+
+ for (unsigned int i = 0; i < _num_outputs; i++) {
+ esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
+ esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
+ esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
+ esc.esc[i].esc_voltage = (uint16_t) 0;
+ esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
+ esc.esc[i].esc_rpm = (uint16_t) 0;
+ esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
+ if (Motor[i].Version == 1) {
+ // BLCtrl 2.0 (11Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t) (Motor[i].SetPoint<<3) | Motor[i].SetPointLowerBits;
+ } else {
+ // BLCtrl < 2.0 (8Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
+ }
+ esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
+ esc.esc[i].esc_state = (uint16_t) Motor[i].State;
+ esc.esc[i].esc_errorcount = (uint16_t) 0;
+ }
+
+ orb_publish(ORB_ID(esc_status), _t_esc_status, &esc);
+ }
+
}
+ //::close(_t_esc_status);
::close(_t_actuators);
::close(_t_actuators_effective);
::close(_t_armed);
@@ -715,17 +775,17 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput)
fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i, Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature);
}
- if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
- _task_should_exit = true;
+
+ if(!_overrideSecurityChecks) {
+ if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
+ _task_should_exit = true;
+ }
}
}
return foundMotorCount;
}
-
-
-
int
MK::mk_servo_set(unsigned int chan, short val)
{
@@ -738,17 +798,15 @@ MK::mk_servo_set(unsigned int chan, short val)
tmpVal = val;
- if (tmpVal > 1024) {
- tmpVal = 1024;
+ if (tmpVal > 2047) {
+ tmpVal = 2047;
} else if (tmpVal < 0) {
tmpVal = 0;
}
- Motor[chan].SetPoint = (uint8_t)(tmpVal / 4);
- //Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 4;
-
- Motor[chan].SetPointLowerBits = 0;
+ Motor[chan].SetPoint = (uint8_t)(tmpVal>>3)&0xff;
+ Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal%8)&0x07;
if (_armed == false) {
Motor[chan].SetPoint = 0;
@@ -1014,8 +1072,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1):
if (arg < 2150) {
Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg;
- mk_servo_set_value(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 1024));
-
+ mk_servo_set(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 2047));
} else {
ret = -EINVAL;
}
@@ -1112,25 +1169,19 @@ ssize_t
MK::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
- // loeschen uint16_t values[4];
uint16_t values[8];
- // loeschen if (count > 4) {
- // loeschen // we only have 4 PWM outputs on the FMU
- // loeschen count = 4;
- // loeschen }
if (count > _num_outputs) {
// we only have 8 I2C outputs in the driver
count = _num_outputs;
}
-
// allow for misaligned values
memcpy(values, buffer, count * 2);
for (uint8_t i = 0; i < count; i++) {
Motor[i].RawPwmValue = (unsigned short)values[i];
- mk_servo_set_value(i, scaling(values[i], 1010, 2100, 0, 1024));
+ mk_servo_set(i, scaling(values[i], 1010, 2100, 0, 2047));
}
return count * 2;
@@ -1282,7 +1333,7 @@ enum FrameType {
PortMode g_port_mode;
int
-mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype)
+mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks)
{
uint32_t gpio_bits;
int shouldStop = 0;
@@ -1341,6 +1392,9 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
/* motortest if enabled */
g_mk->set_motor_test(motortest);
+ /* ovveride security checks if enabled */
+ g_mk->set_overrideSecurityChecks(overrideSecurityChecks);
+
/* count used motors */
do {
@@ -1406,6 +1460,7 @@ mkblctrl_main(int argc, char *argv[])
int px4mode = MAPPING_PX4;
int frametype = FRAME_PLUS; // + plus is default
bool motortest = false;
+ bool overrideSecurityChecks = false;
bool showHelp = false;
bool newMode = false;
@@ -1461,11 +1516,21 @@ mkblctrl_main(int argc, char *argv[])
showHelp = true;
}
+ /* look for the optional --override-security-checks parameter */
+ if (strcmp(argv[i], "--override-security-checks") == 0) {
+ overrideSecurityChecks = true;
+ newMode = true;
+ }
+
}
if (showHelp) {
fprintf(stderr, "mkblctrl: help:\n");
- fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n");
+ fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [--override-security-checks] [-h / --help]\n\n");
+ fprintf(stderr, "\t -mkmode frame {+/x} \t\t Type of frame, if Mikrokopter motor order is used.\n");
+ fprintf(stderr, "\t -b i2c_bus_number \t\t Set the i2c bus where the ESCs are connected to (default 1).\n");
+ fprintf(stderr, "\t -t motortest \t\t\t Spin up once every motor in order of motoraddress. (DANGER !!!)\n");
+ fprintf(stderr, "\t --override-security-checks \t\t Disable all security checks (arming and number of ESCs). Used to test single Motors etc. (DANGER !!!)\n");
exit(1);
}
@@ -1483,7 +1548,7 @@ mkblctrl_main(int argc, char *argv[])
/* parameter set ? */
if (newMode) {
/* switch parameter */
- return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype);
+ return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks);
}
/* test, etc. here g*/
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index bf72892eb..5147ac500 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -239,7 +239,7 @@ PX4FMU::init()
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("fmuservo",
+ _task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 8b2fae12b..19163cebe 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -106,7 +106,7 @@ public:
* @param rate The rate in Hz actuator outpus are sent to IO.
* Min 10 Hz, max 400 Hz
*/
- int set_update_rate(int rate);
+ int set_update_rate(int rate);
/**
* Set the battery current scaling and bias
@@ -114,7 +114,15 @@ public:
* @param amp_per_volt
* @param amp_bias
*/
- void set_battery_current_scaling(float amp_per_volt, float amp_bias);
+ void set_battery_current_scaling(float amp_per_volt, float amp_bias);
+
+ /**
+ * Push failsafe values to IO.
+ *
+ * @param vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
+ * @param len Number of channels, could up to 8
+ */
+ int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
* Print the current status of IO
@@ -326,11 +334,11 @@ PX4IO::PX4IO() :
_to_actuators_effective(0),
_to_outputs(0),
_to_battery(0),
+ _primary_pwm_device(false),
_battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
_battery_mamphour_total(0),
- _battery_last_timestamp(0),
- _primary_pwm_device(false)
+ _battery_last_timestamp(0)
{
/* we need this potentially before it could be set in task_main */
g_dev = this;
@@ -690,6 +698,19 @@ PX4IO::io_set_control_state()
}
int
+PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, vals, len);
+}
+
+int
PX4IO::io_set_arming_state()
{
actuator_armed_s armed; ///< system armed state
@@ -1250,7 +1271,7 @@ PX4IO::print_status()
printf("%u bytes free\n",
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
- printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s\n",
+ printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
flags,
((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""),
((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
@@ -1262,7 +1283,8 @@ PX4IO::print_status()
((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PPM" : ""),
((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
- ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"));
+ ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : ""));
uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
printf("alarms 0x%04x%s%s%s%s%s%s%s\n",
alarms,
@@ -1280,7 +1302,7 @@ PX4IO::print_status()
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
- printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n",
+ printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n",
(double)_battery_amp_per_volt,
(double)_battery_amp_bias,
(double)_battery_mamphour_total);
@@ -1474,7 +1496,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
- ret = mixer_send(buf, strnlen(buf, 1024));
+ ret = mixer_send(buf, strnlen(buf, 2048));
break;
}
@@ -1615,6 +1637,13 @@ test(void)
if (ioctl(fd, PWM_SERVO_ARM, 0))
err(1, "failed to arm servos");
+ /* Open console directly to grab CTRL-C signal */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
for (;;) {
/* sweep all servos between 1000..2000 */
@@ -1649,6 +1678,16 @@ test(void)
if (value != servos[i])
errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
}
+
+ /* Check if user wants to quit */
+ char c;
+ if (read(console, &c, 1) == 1) {
+ if (c == 0x03 || c == 0x63) {
+ warnx("User abort\n");
+ close(console);
+ exit(0);
+ }
+ }
}
}
@@ -1718,6 +1757,41 @@ px4io_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "failsafe")) {
+
+ if (argc < 3) {
+ errx(1, "failsafe command needs at least one channel value (ppm)");
+ }
+
+ if (g_dev != nullptr) {
+
+ /* set values for first 8 channels, fill unassigned channels with 1500. */
+ uint16_t failsafe[8];
+
+ for (int i = 0; i < sizeof(failsafe) / sizeof(failsafe[0]); i++)
+ {
+ /* set channel to commanline argument or to 900 for non-provided channels */
+ if (argc > i + 2) {
+ failsafe[i] = atoi(argv[i+2]);
+ if (failsafe[i] < 800 || failsafe[i] > 2200) {
+ errx(1, "value out of range of 800 < value < 2200. Aborting.");
+ }
+ } else {
+ /* a zero value will result in stopping to output any pulse */
+ failsafe[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting failsafe values");
+ } else {
+ errx(1, "not loaded");
+ }
+ exit(0);
+ }
+
if (!strcmp(argv[1], "recovery")) {
if (g_dev != nullptr) {
@@ -1845,5 +1919,5 @@ px4io_main(int argc, char *argv[])
monitor();
out:
- errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current' or 'update'");
+ errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe' or 'update'");
}
diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/uploader.cpp
index 15524c3ae..9e3f041e3 100644
--- a/src/drivers/px4io/uploader.cpp
+++ b/src/drivers/px4io/uploader.cpp
@@ -49,6 +49,7 @@
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
+#include <termios.h>
#include <sys/stat.h>
#include "uploader.h"
@@ -121,6 +122,12 @@ PX4IO_Uploader::upload(const char *filenames[])
return -errno;
}
+ /* adjust line speed to match bootloader */
+ struct termios t;
+ tcgetattr(_io_fd, &t);
+ cfsetspeed(&t, 115200);
+ tcsetattr(_io_fd, TCSANOW, &t);
+
/* look for the bootloader */
ret = sync();
@@ -251,7 +258,7 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
int ret = ::poll(&fds[0], 1, timeout);
if (ret < 1) {
- log("poll timeout %d", ret);
+ //log("poll timeout %d", ret);
return -ETIMEDOUT;
}
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 911def943..1020eb946 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -58,7 +58,7 @@
#include <drivers/drv_adc.h>
#include <arch/stm32/chip.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <systemlib/err.h>
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index fd63681e3..7ef3db970 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -66,7 +66,7 @@
#include "up_internal.h"
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
@@ -278,8 +278,10 @@ static void hrt_call_invoke(void);
#ifdef CONFIG_HRT_PPM
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
+ *
+ * Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
*/
-# ifndef GTIM_CCER_CC1NP
+# ifdef CONFIG_ARCH_CORTEXM3
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index c1efb8515..7b060412c 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -64,7 +64,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index ac5511e60..167ef30a8 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -111,7 +111,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>