From 92e1d5eb78d9d04a89b0413718c8bab6e9af7f63 Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 28 Nov 2012 20:12:36 -0800 Subject: Possible fix for #78 - increase the wait timeout for discard when flashing PX4IO. It's not clear this solves the issue, but I can't reproduce it with this added. --- apps/drivers/px4io/uploader.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) (limited to 'apps/drivers') diff --git a/apps/drivers/px4io/uploader.cpp b/apps/drivers/px4io/uploader.cpp index 5669aeb01..8b354ff60 100644 --- a/apps/drivers/px4io/uploader.cpp +++ b/apps/drivers/px4io/uploader.cpp @@ -189,8 +189,10 @@ PX4IO_Uploader::drain() int ret; do { - ret = recv(c, 10); - //log("discard 0x%02x", c); + ret = recv(c, 250); + if (ret == OK) { + //log("discard 0x%02x", c); + } } while (ret == OK); } -- cgit v1.2.3 From d0efd1a419497ec2fadb7b516cd2f9cc5a09ca5d Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 29 Nov 2012 00:35:21 -0800 Subject: Fix the DSM (spektrum) protocol decoder, and add some format auto-detection to it. --- apps/drivers/px4io/px4io.cpp | 30 +++++---- apps/px4io/comms.c | 7 +- apps/px4io/dsm.c | 154 +++++++++++++++++++++++++++++++++++++------ apps/px4io/protocol.h | 5 +- 4 files changed, 156 insertions(+), 40 deletions(-) (limited to 'apps/drivers') diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index f2c87473c..11f2f6f68 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -637,10 +637,12 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) void PX4IO::set_rx_mode(unsigned mode) { - if (mode != _rx_mode) { - _rx_mode = mode; - _config_needed = true; - } + /* + * Always (re)set the rx mode; makes testing + * easier after PX4IO has been restarted. + */ + _rx_mode = mode; + _config_needed = true; } extern "C" __EXPORT int px4io_main(int argc, char *argv[]); @@ -744,25 +746,29 @@ px4io_main(int argc, char *argv[]) return ret; } - if (!strcmp(argv[1], "rx_dsm_10bit")) { + if (!strcmp(argv[1], "rx_dsm") || + !strcmp(argv[1], "rx_dsm_10bit") || + !strcmp(argv[1], "rx_dsm_11bit")) { if (g_dev == nullptr) errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_DSM_10BIT); + g_dev->set_rx_mode(RX_MODE_DSM); + exit(0); } - if (!strcmp(argv[1], "rx_dsm_11bit")) { + if (!strcmp(argv[1], "rx_sbus")) { if (g_dev == nullptr) errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_DSM_11BIT); + g_dev->set_rx_mode(RX_MODE_FUTABA_SBUS); + exit(0); } - if (!strcmp(argv[1], "rx_sbus")) { + if (!strcmp(argv[1], "rx_ppm")) { if (g_dev == nullptr) errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_FUTABA_SBUS); + g_dev->set_rx_mode(RX_MODE_PPM_ONLY); + exit(0); } if (!strcmp(argv[1], "test")) test(); - - errx(1, "need a command, try 'start', 'test', 'rx_dsm_10bit', 'rx_dsm_11bit', 'rx_sbus' or 'update'"); + errx(1, "need a command, try 'start', 'test', 'rx_ppm', 'rx_dsm', 'rx_sbus' or 'update'"); } diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index f1dac433f..c44b677d1 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -112,9 +112,7 @@ serial_rx_init(unsigned serial_mode) tcgetattr(rx_fd, &t); switch (serial_mode) { - case RX_MODE_DSM_10BIT: - case RX_MODE_DSM_11BIT: - + case RX_MODE_DSM: /* 115200, no parity, one stop bit */ cfsetspeed(&t, 115200); t.c_cflag &= ~(CSTOPB | PARENB); @@ -163,8 +161,7 @@ comms_check(void) */ if ((pollcount > 1) && (pollfds[1].revents & POLLIN)) { switch (system_state.serial_rx_mode) { - case RX_MODE_DSM_10BIT: - case RX_MODE_DSM_11BIT: + case RX_MODE_DSM: dsm_input(rx_fd); break; diff --git a/apps/px4io/dsm.c b/apps/px4io/dsm.c index 79b6301c7..4384ab523 100644 --- a/apps/px4io/dsm.c +++ b/apps/px4io/dsm.c @@ -49,12 +49,15 @@ #include +#define DEBUG + #include "px4io.h" #include "protocol.h" #define DSM_FRAME_SIZE 16 #define DSM_FRAME_CHANNELS 7 +static hrt_abstime last_rx_time; static hrt_abstime last_frame_time; static uint8_t frame[DSM_FRAME_SIZE]; @@ -63,21 +66,21 @@ static unsigned partial_frame_count; static bool insync; static unsigned channel_shift; -static void dsm_decode(void); +static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value); +static void dsm_guess_format(bool reset); +static void dsm_decode(hrt_abstime now); void dsm_init(unsigned mode) { insync = false; partial_frame_count = 0; + last_rx_time = hrt_absolute_time(); - if (mode == RX_MODE_DSM_10BIT) { - channel_shift = 10; - } else { - channel_shift = 11; - } + /* reset the format detector */ + dsm_guess_format(true); - last_frame_time = hrt_absolute_time(); + debug("DSM: enabled and waiting\n"); } void @@ -97,10 +100,17 @@ dsm_input(int fd) * We expect to only be called when bytes arrive for processing, * and if an interval of more than 5ms passes between calls, * the first byte we read will be the first byte of a frame. + * + * In the case where byte(s) are dropped from a frame, this also + * provides a degree of protection. Of course, it would be better + * if we didn't drop bytes... */ now = hrt_absolute_time(); - if ((now - last_frame_time) > 5000) + if ((now - last_rx_time) > 5000) { + if (partial_frame_count > 0) + debug("DSM: reset @ %d", partial_frame_count); partial_frame_count = 0; + } /* * Fetch bytes, but no more than we would need to complete @@ -111,6 +121,7 @@ dsm_input(int fd) /* if the read failed for any reason, just give up here */ if (ret < 1) return; + last_rx_time = now; /* * Add bytes to the current frame @@ -123,20 +134,125 @@ dsm_input(int fd) */ if (partial_frame_count < DSM_FRAME_SIZE) return; - last_frame_time = now; /* * Great, it looks like we might have a frame. Go ahead and * decode it. */ - dsm_decode(); + dsm_decode(now); partial_frame_count = 0; } +static bool +dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value) +{ + + if (raw == 0xffff) + return false; + + *channel = (raw >> shift) & 0xf; + + uint16_t data_mask = (1 << shift) - 1; + *value = raw & data_mask; + + //debug("DSM: %d 0x%04x -> %d %d", shift, raw, *channel, *value); + + return true; +} + static void -dsm_decode(void) +dsm_guess_format(bool reset) { - uint16_t data_mask = (1 << channel_shift) - 1; + static uint32_t cs10; + static uint32_t cs11; + static unsigned samples; + + /* reset the 10/11 bit sniffed channel masks */ + if (reset) { + cs10 = 0; + cs11 = 0; + samples = 0; + channel_shift = 0; + return; + } + + /* scan the channels in the current frame in both 10- and 11-bit mode */ + for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) { + + uint8_t *dp = &frame[2 + (2 * i)]; + uint16_t raw = (dp[0] << 8) | dp[1]; + unsigned channel, value; + + /* if the channel decodes, remember the assigned number */ + if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31)) + cs10 |= (1 << channel); + if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31)) + cs11 |= (1 << channel); + + /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */ + } + + /* wait until we have seen plenty of frames - 2 should normally be enough */ + if (samples++ < 5) + return; + + /* + * Iterate the set of sensible sniffed channel sets and see whether + * decoding in 10 or 11-bit mode has yielded anything we recognise. + */ + static uint32_t masks[] = { + 0x3f, /* 6 channels (DX6) */ + 0x7f, /* 7 channels (DX7) */ + 0xff, /* 8 channels (DX8) */ + 0x3ff, /* 10 channels (DX10) */ + 0x3fff /* 18 channels (DX10) */ + }; + unsigned votes10 = 0; + unsigned votes11 = 0; + + for (unsigned i = 0; i < (sizeof(masks) / sizeof(masks[0])); i++) { + + if (cs10 == masks[i]) + votes10++; + if (cs11 == masks[i]) + votes11++; + } + if ((votes11 == 1) && (votes10 == 0)) { + channel_shift = 11; + debug("DSM: detected 11-bit format"); + return; + } + if ((votes10 == 1) && (votes11 == 0)) { + channel_shift = 10; + debug("DSM: detected 10-bit format"); + return; + } + + /* call ourselves to reset our state ... we have to try again */ + debug("DSM: format detector failed, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11); + dsm_guess_format(true); +} + +static void +dsm_decode(hrt_abstime frame_time) +{ + +/* + debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x", + frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7], + frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]); +*/ + /* + * If we have lost signal for at least a second, reset the + * format guessing heuristic. + */ + if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0)) + dsm_guess_format(true); + last_frame_time = frame_time; + if (channel_shift == 0) { + dsm_guess_format(false); + return; + } /* * The encoding of the first byte is uncertain, so we're going @@ -159,26 +275,24 @@ dsm_decode(void) uint8_t *dp = &frame[2 + (2 * i)]; uint16_t raw = (dp[0] << 8) | dp[1]; + unsigned channel, value; - /* ignore pad channels */ - if (raw == 0xffff) + if (!dsm_decode_channel(raw, channel_shift, &channel, &value)) continue; - unsigned channel = (raw >> channel_shift) & 0xf; - /* ignore channels out of range */ if (channel >= PX4IO_INPUT_CHANNELS) continue; + /* update the decoded channel count */ if (channel > ppm_decoded_channels) ppm_decoded_channels = channel; /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */ - unsigned data = raw & data_mask; if (channel_shift == 11) - data /= 2; - ppm_buffer[channel] = 988 + data; - + value /= 2; + ppm_buffer[channel] = 988 + value; } + ppm_last_valid_decode = hrt_absolute_time(); } diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h index 660eed12b..8d051d385 100644 --- a/apps/px4io/protocol.h +++ b/apps/px4io/protocol.h @@ -64,9 +64,8 @@ struct px4io_config { uint8_t serial_rx_mode; #define RX_MODE_PPM_ONLY 0 -#define RX_MODE_DSM_10BIT 1 -#define RX_MODE_DSM_11BIT 2 -#define RX_MODE_FUTABA_SBUS 3 +#define RX_MODE_DSM 1 +#define RX_MODE_FUTABA_SBUS 2 }; /* report from IO to FMU */ -- cgit v1.2.3 From 9fa794a8faa2d30023d9943beae55a05ed4e48a0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 30 Nov 2012 00:02:47 -0800 Subject: Rework the PX4IO software architecture: - Use a separate thread for handing R/C inputs and outputs. - Remove all PX4IO R/C receiver configuration; it's all automatic now. - Rework the main loop, dedicate it to PX4FMU communications after startup. - Fix several issues in the px4io driver that would cause a crash if PX4IO was not responding. --- apps/drivers/px4io/px4io.cpp | 96 ++++++++++----------------- apps/px4io/comms.c | 153 +++++++++++-------------------------------- apps/px4io/controls.c | 88 +++++++++++++++++++++++++ apps/px4io/dsm.c | 56 +++++++++++----- apps/px4io/mixer.c | 27 +------- apps/px4io/protocol.h | 5 +- apps/px4io/px4io.c | 103 ++++++----------------------- apps/px4io/px4io.h | 15 +++-- apps/px4io/safety.c | 36 ++++++++++ apps/px4io/sbus.c | 29 ++++++-- 10 files changed, 294 insertions(+), 314 deletions(-) create mode 100644 apps/px4io/controls.c (limited to 'apps/drivers') diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 11f2f6f68..80a61e303 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -87,15 +87,13 @@ public: virtual int ioctl(file *filp, int cmd, unsigned long arg); - void set_rx_mode(unsigned mode); - private: static const unsigned _max_actuators = PX4IO_OUTPUT_CHANNELS; int _serial_fd; ///< serial interface to PX4IO hx_stream_t _io_stream; ///< HX protocol stream - int _task; ///< worker task + volatile int _task; ///< worker task volatile bool _task_should_exit; volatile bool _connected; ///< true once we have received a valid frame @@ -121,8 +119,6 @@ private: bool _send_needed; ///< If true, we need to send a packet to IO bool _config_needed; ///< if true, we need to set a config update to IO - uint8_t _rx_mode; ///< the current RX mode on IO - /** * Trampoline to the worker task */ @@ -190,8 +186,7 @@ PX4IO::PX4IO() : _primary_pwm_device(false), _switch_armed(false), _send_needed(false), - _config_needed(false), - _rx_mode(RX_MODE_PPM_ONLY) + _config_needed(false) { /* we need this potentially before it could be set in task_main */ g_dev = this; @@ -201,33 +196,17 @@ PX4IO::PX4IO() : PX4IO::~PX4IO() { - if (_task != -1) { - /* tell the task we want it to go away */ - _task_should_exit = true; - - /* spin waiting for the thread to stop */ - unsigned i = 10; - - do { - /* wait 50ms - it should wake every 100ms or so worst-case */ - usleep(50000); - - /* if we have given up, kill it */ - if (--i == 0) { - task_delete(_task); - break; - } + /* tell the task we want it to go away */ + _task_should_exit = true; - } while (_task != -1); + /* spin waiting for the task to stop */ + for (unsigned i = 0; (i < 10) && (_task != -1); i++) { + /* give it another 100ms */ + usleep(100000); } - - /* clean up the alternate device node */ - if (_primary_pwm_device) - unregister_driver(PWM_OUTPUT_DEVICE_PATH); - - /* kill the HX stream */ - if (_io_stream != nullptr) - hx_stream_free(_io_stream); + /* well, kill it anyway, though this will probably crash */ + if (_task != -1) + task_delete(_task); g_dev = nullptr; } @@ -295,6 +274,16 @@ PX4IO::task_main() goto out; } + /* 115200bps, no parity, one stop bit */ + { + struct termios t; + + tcgetattr(_serial_fd, &t); + cfsetspeed(&t, 115200); + t.c_cflag &= ~(CSTOPB | PARENB); + tcsetattr(_serial_fd, TCSANOW, &t); + } + /* protocol stream */ _io_stream = hx_stream_init(_serial_fd, &PX4IO::rx_callback_trampoline, this); if (_io_stream == nullptr) { @@ -402,8 +391,16 @@ PX4IO::task_main() } out: + debug("exiting"); + + /* kill the HX stream */ if (_io_stream != nullptr) hx_stream_free(_io_stream); + ::close(_serial_fd); + + /* clean up the alternate device node */ + if (_primary_pwm_device) + unregister_driver(PWM_OUTPUT_DEVICE_PATH); /* tell the dtor that we are exiting */ _task = -1; @@ -514,7 +511,6 @@ PX4IO::config_send() int ret; cfg.f2i_config_magic = F2I_CONFIG_MAGIC; - cfg.serial_rx_mode = _rx_mode; ret = hx_stream_send(_io_stream, &cfg, sizeof(cfg)); if (ret) @@ -634,17 +630,6 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) return ret; } -void -PX4IO::set_rx_mode(unsigned mode) -{ - /* - * Always (re)set the rx mode; makes testing - * easier after PX4IO has been restarted. - */ - _rx_mode = mode; - _config_needed = true; -} - extern "C" __EXPORT int px4io_main(int argc, char *argv[]); namespace @@ -748,25 +733,10 @@ px4io_main(int argc, char *argv[]) if (!strcmp(argv[1], "rx_dsm") || !strcmp(argv[1], "rx_dsm_10bit") || - !strcmp(argv[1], "rx_dsm_11bit")) { - if (g_dev == nullptr) - errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_DSM); - exit(0); - } - if (!strcmp(argv[1], "rx_sbus")) { - if (g_dev == nullptr) - errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_FUTABA_SBUS); - exit(0); - } - if (!strcmp(argv[1], "rx_ppm")) { - if (g_dev == nullptr) - errx(1, "not started"); - g_dev->set_rx_mode(RX_MODE_PPM_ONLY); - exit(0); - } - + !strcmp(argv[1], "rx_dsm_11bit") || + !strcmp(argv[1], "rx_sbus") || + !strcmp(argv[1], "rx_ppm")) + errx(0, "receiver type is automatically detected, option '%s' is deprecated", argv[1]); if (!strcmp(argv[1], "test")) test(); diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index c44b677d1..a93ef9cb8 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -32,10 +32,11 @@ ****************************************************************************/ /** - * @file FMU communication for the PX4IO module. + * @file comms.c + * + * FMU communication for the PX4IO module. */ - #include #include #include @@ -44,7 +45,6 @@ #include #include #include -#include #include #include @@ -54,101 +54,50 @@ #include #include +#define DEBUG #include "px4io.h" #define FMU_MIN_REPORT_INTERVAL 5000 /* 5ms */ #define FMU_MAX_REPORT_INTERVAL 100000 /* 100ms */ +int frame_rx; +int frame_bad; + static int fmu_fd; static hx_stream_t stream; -static int rx_fd; static struct px4io_report report; static void comms_handle_frame(void *arg, const void *buffer, size_t length); -static struct pollfd pollfds[2]; -static int pollcount; - void comms_init(void) { /* initialise the FMU interface */ fmu_fd = open("/dev/ttyS1", O_RDWR | O_NONBLOCK); - if (fmu_fd < 0) - lib_lowprintf("COMMS: fmu open failed %d\n", errno); stream = hx_stream_init(fmu_fd, comms_handle_frame, NULL); - pollfds[0].fd = fmu_fd; - pollfds[0].events = POLLIN; - pollcount = 1; /* default state in the report to FMU */ report.i2f_magic = I2F_MAGIC; - } -static void -serial_rx_init(unsigned serial_mode) +void +comms_main(void) { - if (serial_mode == system_state.serial_rx_mode) - return; - system_state.serial_rx_mode = serial_mode; - - if (serial_mode == RX_MODE_PPM_ONLY) { - if (rx_fd != -1) { - pollcount = 1; - close(rx_fd); - rx_fd = -1; - } - return; - } - - /* open the serial port used for DSM and S.bus communication */ - rx_fd = open("/dev/ttyS0", O_RDONLY | O_NONBLOCK); - pollfds[1].fd = rx_fd; - pollfds[1].events = POLLIN; - pollcount = 2; - - struct termios t; - tcgetattr(rx_fd, &t); - switch (serial_mode) { - case RX_MODE_DSM: - /* 115200, no parity, one stop bit */ - cfsetspeed(&t, 115200); - t.c_cflag &= ~(CSTOPB | PARENB); + struct pollfd fds; + fds.fd = fmu_fd; + fds.events = POLLIN; + debug("FMU: ready"); - dsm_init(serial_mode); - break; + for (;;) { + /* wait for serial data, but no more than 100ms */ + poll(&fds, 1, 100); - case RX_MODE_FUTABA_SBUS: - /* 100000, even parity, two stop bits */ - cfsetspeed(&t, 100000); - t.c_cflag |= (CSTOPB | PARENB); - - sbus_init(serial_mode); - break; - - default: - break; - } - - tcsetattr(rx_fd, TCSANOW, &t); -} - -void -comms_check(void) -{ - /* - * Check for serial data - */ - int ret = poll(pollfds, pollcount, 0); - - if (ret > 0) { /* * Pull bytes from FMU and feed them to the HX engine. * Limit the number of bytes we actually process on any one iteration. */ - if (pollfds[0].revents & POLLIN) { + if (fds.revents & POLLIN) { char buf[32]; ssize_t count = read(fmu_fd, buf, sizeof(buf)); for (int i = 0; i < count; i++) @@ -156,54 +105,32 @@ comms_check(void) } /* - * Pull bytes from the serial RX port and feed them to the decoder - * if we care about serial RX data. + * Decide if it's time to send an update to the FMU. */ - if ((pollcount > 1) && (pollfds[1].revents & POLLIN)) { - switch (system_state.serial_rx_mode) { - case RX_MODE_DSM: - dsm_input(rx_fd); - break; - - case RX_MODE_FUTABA_SBUS: - sbus_input(rx_fd); - break; - - default: - break; - } + static hrt_abstime last_report_time; + hrt_abstime now, delta; + + /* should we send a report to the FMU? */ + now = hrt_absolute_time(); + delta = now - last_report_time; + if ((delta > FMU_MIN_REPORT_INTERVAL) && + (system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) { + + system_state.fmu_report_due = false; + last_report_time = now; + + /* populate the report */ + for (int i = 0; i < system_state.rc_channels; i++) + report.rc_channel[i] = system_state.rc_channel_data[i]; + report.channel_count = system_state.rc_channels; + report.armed = system_state.armed; + + /* and send it */ + hx_stream_send(stream, &report, sizeof(report)); } } - - /* - * Decide if it's time to send an update to the FMU. - */ - static hrt_abstime last_report_time; - hrt_abstime now, delta; - - /* should we send a report to the FMU? */ - now = hrt_absolute_time(); - delta = now - last_report_time; - if ((delta > FMU_MIN_REPORT_INTERVAL) && - (system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) { - - system_state.fmu_report_due = false; - last_report_time = now; - - /* populate the report */ - for (int i = 0; i < system_state.rc_channels; i++) - report.rc_channel[i] = system_state.rc_channel_data[i]; - report.channel_count = system_state.rc_channels; - report.armed = system_state.armed; - - /* and send it */ - hx_stream_send(stream, &report, sizeof(report)); - } } -int frame_rx; -int frame_bad; - static void comms_handle_config(const void *buffer, size_t length) { @@ -215,8 +142,6 @@ comms_handle_config(const void *buffer, size_t length) } frame_rx++; - - serial_rx_init(cfg->serial_rx_mode); } static void @@ -274,9 +199,9 @@ comms_handle_frame(void *arg, const void *buffer, size_t length) comms_handle_config(buffer, length); break; default: + frame_bad++; break; } } - frame_bad++; } diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c new file mode 100644 index 000000000..d4eace3df --- /dev/null +++ b/apps/px4io/controls.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 controls.c + * + * R/C inputs and servo outputs. + */ + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#define DEBUG +#include "px4io.h" + +void +controls_main(void) +{ + struct pollfd fds[2]; + + fds[0].fd = dsm_init("/dev/ttyS0"); + fds[0].events = POLLIN; + + + fds[1].fd = sbus_init("/dev/ttyS2"); + fds[1].events = POLLIN; + + for (;;) { + /* run this loop at ~100Hz */ + poll(fds, 2, 10); + + if (fds[0].revents & POLLIN) + dsm_input(); + if (fds[1].revents & POLLIN) + sbus_input(); + + /* XXX do ppm processing, bypass mode, etc. here */ + + /* do PWM output updates */ + mixer_tick(); + } +} diff --git a/apps/px4io/dsm.c b/apps/px4io/dsm.c index 0e9fd25f1..da7d1a361 100644 --- a/apps/px4io/dsm.c +++ b/apps/px4io/dsm.c @@ -44,6 +44,7 @@ #include #include #include +#include #include @@ -57,6 +58,8 @@ #define DSM_FRAME_SIZE 16 #define DSM_FRAME_CHANNELS 7 +static int dsm_fd = -1; + static hrt_abstime last_rx_time; static hrt_abstime last_frame_time; @@ -66,27 +69,46 @@ static unsigned partial_frame_count; static bool insync; static unsigned channel_shift; +unsigned dsm_frame_drops; + static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value); static void dsm_guess_format(bool reset); static void dsm_decode(hrt_abstime now); -void -dsm_init(unsigned mode) +int +dsm_init(const char *device) { - insync = false; - partial_frame_count = 0; - last_rx_time = hrt_absolute_time(); + if (dsm_fd < 0) + dsm_fd = open(device, O_RDONLY); - /* reset the format detector */ - dsm_guess_format(true); + if (dsm_fd >= 0) { + struct termios t; + + /* 115200bps, no parity, one stop bit */ + tcgetattr(dsm_fd, &t); + cfsetspeed(&t, 115200); + t.c_cflag &= ~(CSTOPB | PARENB); + tcsetattr(dsm_fd, TCSANOW, &t); + + /* initialise the decoder */ + insync = false; + partial_frame_count = 0; + last_rx_time = hrt_absolute_time(); + + /* reset the format detector */ + dsm_guess_format(true); - debug("DSM: enabled and waiting\n"); + debug("DSM: ready"); + } else { + debug("DSM: open failed"); + } + + return dsm_fd; } void -dsm_input(int fd) +dsm_input(void) { - uint8_t buf[DSM_FRAME_SIZE]; ssize_t ret; hrt_abstime now; @@ -107,16 +129,17 @@ dsm_input(int fd) */ now = hrt_absolute_time(); if ((now - last_rx_time) > 5000) { - if (partial_frame_count > 0) - debug("DSM: reset @ %d", partial_frame_count); - partial_frame_count = 0; + if (partial_frame_count > 0) { + dsm_frame_drops++; + partial_frame_count = 0; + } } /* * Fetch bytes, but no more than we would need to complete * the current frame. */ - ret = read(fd, buf, DSM_FRAME_SIZE - partial_frame_count); + ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count); /* if the read failed for any reason, just give up here */ if (ret < 1) @@ -126,7 +149,6 @@ dsm_input(int fd) /* * Add bytes to the current frame */ - memcpy(&frame[partial_frame_count], buf, ret); partial_frame_count += ret; /* @@ -292,8 +314,12 @@ dsm_decode(hrt_abstime frame_time) /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */ if (channel_shift == 11) value /= 2; + + /* stuff the decoded channel into the PPM input buffer */ ppm_buffer[channel] = 988 + value; } + /* and note that we have received data from the R/C controller */ + /* XXX failsafe will cause problems here - need a strategy for detecting it */ ppm_last_valid_decode = hrt_absolute_time(); } diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c index 572344d00..61e716474 100644 --- a/apps/px4io/mixer.c +++ b/apps/px4io/mixer.c @@ -60,17 +60,6 @@ */ static unsigned fmu_input_drops; #define FMU_INPUT_DROP_LIMIT 20 - -/* - * HRT periodic call used to check for control input data. - */ -static struct hrt_call mixer_input_call; - -/* - * Mixer periodic tick. - */ -static void mixer_tick(void *arg); - /* * Collect RC input data from the controller source(s). */ @@ -92,20 +81,8 @@ struct mixer { /* XXX more config here */ } mixers[IO_SERVO_COUNT]; -int -mixer_init(void) -{ - - - /* look for control data at 50Hz */ - hrt_call_every(&mixer_input_call, 1000, 20000, mixer_tick, NULL); - - return 0; -} - - -static void -mixer_tick(void *arg) +void +mixer_tick(void) { uint16_t *control_values; int control_count; diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h index 8d051d385..c704b1201 100644 --- a/apps/px4io/protocol.h +++ b/apps/px4io/protocol.h @@ -62,10 +62,7 @@ struct px4io_config { uint16_t f2i_config_magic; #define F2I_CONFIG_MAGIC 0x6366 - uint8_t serial_rx_mode; -#define RX_MODE_PPM_ONLY 0 -#define RX_MODE_DSM 1 -#define RX_MODE_FUTABA_SBUS 2 + /* XXX currently nothing here */ }; /* report from IO to FMU */ diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c index 197bad7c6..ba16ce247 100644 --- a/apps/px4io/px4io.c +++ b/apps/px4io/px4io.c @@ -55,37 +55,15 @@ __EXPORT int user_start(int argc, char *argv[]); struct sys_state_s system_state; -int gpio_fd; - -static const char cursor[] = {'|', '/', '-', '\\'}; - -static struct hrt_call timer_tick_call; -volatile int timers[TIMER_NUM_TIMERS]; -static void timer_tick(void *arg); int user_start(int argc, char *argv[]) { - int cycle = 0; - bool heartbeat = false; - bool failsafe = false; /* configure the high-resolution time/callout interface */ hrt_init(); - /* init the FMU and receiver links */ - comms_init(); - - /* configure the first 8 PWM outputs (i.e. all of them) */ - /* note, must do this after comms init to steal back PA0, which is CTS otherwise */ - up_pwm_servo_init(0xff); - /* print some startup info */ lib_lowprintf("\nPX4IO: starting\n"); - struct mallinfo minfo = mallinfo(); - lib_lowprintf("free %u largest %u\n", minfo.mxordblk, minfo.fordblks); - - /* start the software timer service */ - hrt_call_every(&timer_tick_call, 1000, 1000, timer_tick, NULL); /* default all the LEDs to off while we start */ LED_AMBER(false); @@ -95,66 +73,27 @@ int user_start(int argc, char *argv[]) /* turn on servo power */ POWER_SERVO(true); - /* start the mixer */ - mixer_init(); - /* start the safety switch handler */ safety_init(); - /* set up some timers for the main loop */ - timers[TIMER_BLINK_BLUE] = 250; /* heartbeat blink @ 2Hz */ - timers[TIMER_STATUS_PRINT] = 1000; /* print status message @ 1Hz */ - - /* - * Main loop servicing communication with FMU - */ - while(true) { - - /* check for communication from FMU, send updates */ - comms_check(); - - /* blink the heartbeat LED */ - if (timers[TIMER_BLINK_BLUE] == 0) { - timers[TIMER_BLINK_BLUE] = 250; - LED_BLUE(heartbeat = !heartbeat); - } - - /* blink the failsafe LED if we don't have FMU input */ - if (!system_state.mixer_use_fmu) { - if (timers[TIMER_BLINK_AMBER] == 0) { - timers[TIMER_BLINK_AMBER] = 125; - failsafe = !failsafe; - } - } else { - failsafe = false; - } - LED_AMBER(failsafe); - - /* print some simple status */ -#if 0 - if (timers[TIMER_STATUS_PRINT] == 0) { - timers[TIMER_STATUS_PRINT] = 1000; - lib_lowprintf("%c %s | %s | %s | %s | C=%d F=%d B=%d \r", - cursor[cycle++ & 3], - (system_state.arm_ok ? "FMU_ARMED" : "FMU_SAFE"), - (system_state.armed ? "ARMED" : "SAFE"), - (system_state.rc_channels ? "RC OK" : "NO RC"), - (system_state.mixer_use_fmu ? "FMU OK" : "NO FMU"), - system_state.rc_channels, - frame_rx, frame_bad - ); - } -#endif - } - - /* Should never reach here */ - return ERROR; -} - -static void -timer_tick(void *arg) -{ - for (unsigned i = 0; i < TIMER_NUM_TIMERS; i++) - if (timers[i] > 0) - timers[i]--; -} + /* start the flight control signal handler */ + task_create("FCon", + SCHED_PRIORITY_DEFAULT, + 1024, + (main_t)controls_main, + NULL); + + + /* initialise the FMU communications interface */ + comms_init(); + + /* configure the first 8 PWM outputs (i.e. all of them) */ + /* note, must do this after comms init to steal back PA0, which is CTS otherwise */ + up_pwm_servo_init(0xff); + + struct mallinfo minfo = mallinfo(); + lib_lowprintf("free %u largest %u\n", minfo.mxordblk, minfo.fordblks); + + /* we're done here, go run the communications loop */ + comms_main(); +} \ No newline at end of file diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h index 0a3a4448c..2ecab966d 100644 --- a/apps/px4io/px4io.h +++ b/apps/px4io/px4io.h @@ -147,7 +147,7 @@ extern volatile int timers[TIMER_NUM_TIMERS]; /* * Mixer */ -extern int mixer_init(void); +extern void mixer_tick(void); /* * Safety switch/LED. @@ -158,15 +158,16 @@ extern void safety_init(void); * FMU communications */ extern void comms_init(void); -extern void comms_check(void); +extern void comms_main(void) __attribute__((noreturn)); /* - * Serial receiver decoders. + * R/C receiver handling. */ -extern void dsm_init(unsigned mode); -extern void dsm_input(int fd); -extern void sbus_init(unsigned mode); -extern void sbus_input(int fd); +extern void controls_main(void); +extern int dsm_init(const char *device); +extern void dsm_input(void); +extern int sbus_init(const char *device); +extern void sbus_input(void); /* * Assertion codes diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c index 24fc9951a..d5bd103c1 100644 --- a/apps/px4io/safety.c +++ b/apps/px4io/safety.c @@ -51,6 +51,8 @@ #include "px4io.h" static struct hrt_call arming_call; +static struct hrt_call heartbeat_call; +static struct hrt_call failsafe_call; /* * Count the number of times in a row that we see the arming button @@ -63,13 +65,22 @@ static unsigned counter; static bool safety_led_state; static bool safety_button_pressed; + static void safety_check_button(void *arg); +static void heartbeat_blink(void *arg); +static void failsafe_blink(void *arg); void safety_init(void) { /* arrange for the button handler to be called at 10Hz */ hrt_call_every(&arming_call, 1000, 100000, safety_check_button, NULL); + + /* arrange for the heartbeat handler to be called at 4Hz */ + hrt_call_every(&heartbeat_call, 1000, 250000, heartbeat_blink, NULL); + + /* arrange for the failsafe blinker to be called at 8Hz */ + hrt_call_every(&failsafe_call, 1000, 125000, failsafe_blink, NULL); } static void @@ -117,3 +128,28 @@ safety_check_button(void *arg) } LED_SAFETY(safety_led_state); } + + +static void +heartbeat_blink(void *arg) +{ + static bool heartbeat = false; + + /* XXX add flags here that need to be frobbed by various loops */ + + LED_BLUE(heartbeat = !heartbeat); +} + +static void +failsafe_blink(void *arg) +{ + static bool failsafe = false; + + /* blink the failsafe LED if we don't have FMU input */ + if (!system_state.mixer_use_fmu) { + failsafe = !failsafe; + } else { + failsafe = false; + } + LED_AMBER(failsafe); +} \ No newline at end of file diff --git a/apps/px4io/sbus.c b/apps/px4io/sbus.c index e363a0a78..a91e37b5c 100644 --- a/apps/px4io/sbus.c +++ b/apps/px4io/sbus.c @@ -41,18 +41,39 @@ #include #include +#include #include +#define DEBUG #include "px4io.h" -#include "protocol.h" -void -sbus_init(unsigned mode) +static int sbus_fd = -1; + +int +sbus_init(const char *device) { + if (sbus_fd < 0) + sbus_fd = open(device, O_RDONLY); + + if (sbus_fd >= 0) { + struct termios t; + + /* 100000bps, even parity, two stop bits */ + tcgetattr(sbus_fd, &t); + cfsetspeed(&t, 100000); + t.c_cflag |= (CSTOPB | PARENB); + tcsetattr(sbus_fd, TCSANOW, &t); + + debug("Sbus: ready"); + } else { + debug("Sbus: open failed"); + } + + return sbus_fd; } void -sbus_input(int fd) +sbus_input(void) { } -- cgit v1.2.3 From d16d66f990664481cb8ef6dddd038c575fe16380 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 30 Nov 2012 10:42:27 +0100 Subject: Enabled UART3, added JTAG make target for IO, removed potentially problematic usleep --- Makefile | 15 +++++++++++++-- apps/drivers/px4io/px4io.cpp | 1 - nuttx/configs/px4io/io/defconfig | 2 +- 3 files changed, 14 insertions(+), 4 deletions(-) (limited to 'apps/drivers') diff --git a/Makefile b/Makefile index 801256cfe..d9469bb49 100644 --- a/Makefile +++ b/Makefile @@ -114,10 +114,21 @@ endif upload: $(FIRMWARE_BUNDLE) $(UPLOADER) @python -u $(UPLOADER) --port $(SERIAL_PORTS) $(FIRMWARE_BUNDLE) - + +# +# JTAG firmware uploading with OpenOCD +# +ifeq ($(JTAGCONFIG),) +JTAGCONFIG=interface/olimex-jtag-tiny.cfg +endif + upload-jtag-px4fmu: @echo Attempting to flash PX4FMU board via JTAG - @openocd -f interface/olimex-jtag-tiny.cfg -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown + @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown + +upload-jtag-px4io: all + @echo Attempting to flash PX4IO board via JTAG + @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown # # Hacks and fixups diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 11f2f6f68..a74437d08 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -348,7 +348,6 @@ PX4IO::task_main() /* this would be bad... */ if (ret < 0) { log("poll error %d", errno); - usleep(1000000); continue; } diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig index d354ebfe5..7af9c9e4f 100755 --- a/nuttx/configs/px4io/io/defconfig +++ b/nuttx/configs/px4io/io/defconfig @@ -124,7 +124,7 @@ CONFIG_STM32_TIM7=n CONFIG_STM32_WWDG=n CONFIG_STM32_SPI2=n CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=n +CONFIG_STM32_USART3=y CONFIG_STM32_I2C1=y CONFIG_STM32_I2C2=n CONFIG_STM32_BKP=n -- cgit v1.2.3 From 2ac0cac11f3e3d896efee541eff36be42ff76914 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 30 Nov 2012 21:50:19 -0800 Subject: Build fix - need --- apps/drivers/px4io/px4io.cpp | 1 + 1 file changed, 1 insertion(+) (limited to 'apps/drivers') diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 80a61e303..07a39c881 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -53,6 +53,7 @@ #include #include #include +#include #include #include -- cgit v1.2.3 From de88732e8ecdf1f8451c8c037594f4edb1e2bdc0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Dec 2012 10:49:52 +0100 Subject: Prevented unhealthy RC input from propagating through the system --- apps/drivers/px4io/px4io.cpp | 18 ++++++++++-------- apps/px4io/comms.c | 8 +++++++- 2 files changed, 17 insertions(+), 9 deletions(-) (limited to 'apps/drivers') diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp index 49ad80943..296c541c9 100644 --- a/apps/drivers/px4io/px4io.cpp +++ b/apps/drivers/px4io/px4io.cpp @@ -461,15 +461,17 @@ PX4IO::rx_callback(const uint8_t *buffer, size_t bytes_received) } _connected = true; - /* publish raw rc channel values from IO */ - _input_rc.timestamp = hrt_absolute_time(); - _input_rc.channel_count = rep->channel_count; - for (int i = 0; i < rep->channel_count; i++) - { - _input_rc.values[i] = rep->rc_channel[i]; - } + /* publish raw rc channel values from IO if valid channels are present */ + if (rep->channel_count > 0) { + _input_rc.timestamp = hrt_absolute_time(); + _input_rc.channel_count = rep->channel_count; + for (int i = 0; i < rep->channel_count; i++) + { + _input_rc.values[i] = rep->rc_channel[i]; + } - orb_publish(ORB_ID(input_rc), _to_input_rc, &_input_rc); + orb_publish(ORB_ID(input_rc), _to_input_rc, &_input_rc); + } /* remember the latched arming switch state */ _switch_armed = rep->armed; diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c index 375336730..40ea38cf7 100644 --- a/apps/px4io/comms.c +++ b/apps/px4io/comms.c @@ -132,7 +132,13 @@ comms_main(void) /* populate the report */ for (int i = 0; i < system_state.rc_channels; i++) report.rc_channel[i] = system_state.rc_channel_data[i]; - report.channel_count = system_state.rc_channels; + + if (system_state.sbus_input_ok || system_state.dsm_input_ok || system_state.ppm_input_ok) { + report.channel_count = system_state.rc_channels; + } else { + report.channel_count = 0; + } + report.armed = system_state.armed; /* and send it */ -- cgit v1.2.3