diff --git a/.gitignore b/.gitignore index 85d846b982..8e9075ba49 100644 --- a/.gitignore +++ b/.gitignore @@ -47,6 +47,7 @@ nsh_romfsimg.h cscope.out .configX-e nuttx-export.zip +.~lock.* dot.gdbinit mavlink/include/mavlink/v0.9/ .*.swp diff --git a/Documentation/arming_state_machine.odg b/Documentation/arming_state_machine.odg new file mode 100644 index 0000000000..cfadbab7c9 Binary files /dev/null and b/Documentation/arming_state_machine.odg differ diff --git a/Documentation/arming_state_machine.pdf b/Documentation/arming_state_machine.pdf new file mode 100644 index 0000000000..2c3e8be234 Binary files /dev/null and b/Documentation/arming_state_machine.pdf differ diff --git a/Documentation/flight_mode_state_machine.odg b/Documentation/flight_mode_state_machine.odg new file mode 100644 index 0000000000..b630ecb402 Binary files /dev/null and b/Documentation/flight_mode_state_machine.odg differ diff --git a/Documentation/flight_mode_state_machine.pdf b/Documentation/flight_mode_state_machine.pdf new file mode 100644 index 0000000000..cd234ada73 Binary files /dev/null and b/Documentation/flight_mode_state_machine.pdf differ diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg new file mode 100644 index 0000000000..e35a83372b Binary files /dev/null and b/Documentation/rc_mode_switch.odg differ diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf new file mode 100644 index 0000000000..823b1d8684 Binary files /dev/null and b/Documentation/rc_mode_switch.pdf differ diff --git a/apps/hott_telemetry/Makefile b/apps/hott_telemetry/Makefile new file mode 100644 index 0000000000..8d5faa3b7f --- /dev/null +++ b/apps/hott_telemetry/Makefile @@ -0,0 +1,45 @@ +############################################################################ +# +# 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. +# +############################################################################ + +# +# Graupner HoTT Telemetry application. +# + +# The following line is required for accessing UARTs directly. +INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common + +APPNAME = hott_telemetry +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +include $(APPDIR)/mk/app.mk diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c new file mode 100644 index 0000000000..d67ab06a98 --- /dev/null +++ b/apps/hott_telemetry/hott_telemetry_main.c @@ -0,0 +1,311 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Author: @author Simon Wilks + * + * 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 hott_telemetry_main.c + * + * Graupner HoTT Telemetry implementation. + * + * The HoTT receiver polls each device at a regular interval at which point + * a data packet can be returned if necessary. + * + * TODO: Add support for at least the vario and GPS sensor data. + * + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "messages.h" + +/* The following are equired for UART direct manipulation. */ +#include +#include "up_arch.h" +#include "chip.h" +#include "stm32_internal.h" + +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 ]"; + + +/* 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. + */ +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 open_uart(const char *device, struct termios *uart_config_original) +{ + /* baud rate */ + int speed = B19200; + int uart; + + /* open uart */ + uart = open(device, O_RDWR | O_NOCTTY); + + if (uart < 0) { + char msg[80]; + sprintf(msg, "Error opening port: %s\n", device); + FATAL_MSG(msg); + } + + /* Try to set baud rate */ + struct termios uart_config; + 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); + } + + /* Fill the struct for the new configuration */ + tcgetattr(uart, &uart_config); + + /* Clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* 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); + } + + 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); + } + + /* Activate single wire mode */ + ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); + + return uart; +} + +int read_data(int uart, int *id) +{ + const int timeout = 1000; + struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + + char mode; + + if (poll(fds, 1, timeout) > 0) { + /* Get the mode: binary or text */ + read(uart, &mode, 1); + /* Read the device ID being polled */ + read(uart, id, 1); + + /* if we have a binary mode request */ + if (mode != BINARY_MODE_REQUEST_ID) { + return ERROR; + } + + } else { + ERROR_MSG("UART timeout on TX/RX port"); + return ERROR; + } + + return OK; +} + +int send_data(int uart, uint8_t *buffer, int size) +{ + usleep(POST_READ_DELAY_IN_USECS); + + uint16_t checksum = 0; + + for (int 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; + + } else { + checksum += buffer[i]; + } + + write(uart, &buffer[i], 1); + + /* Sleep before sending the next byte. */ + usleep(POST_WRITE_DELAY_IN_USECS); + } + + /* A hack the reads out what was written so the next read from the receiver doesn't get it. */ + /* TODO: Fix this!! */ + uint8_t dummy[size]; + read(uart, &dummy, size); + + return OK; +} + +int hott_telemetry_thread_main(int argc, char *argv[]) +{ + INFO_MSG("starting"); + + thread_running = true; + + char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ + + /* read commandline arguments */ + for (int i = 0; i < argc && argv[i]; i++) { + if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set + if (argc > i + 1) { + device = argv[i + 1]; + + } else { + thread_running = false; + ERROR_MSG("missing parameter to -d"); + ERROR_MSG(commandline_usage); + exit(1); + } + } + } + + /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ + struct termios uart_config_original; + int uart = open_uart(device, &uart_config_original); + + if (uart < 0) { + ERROR_MSG("Failed opening HoTT UART, exiting."); + thread_running = false; + exit(ERROR); + } + + messages_init(); + + uint8_t buffer[MESSAGE_BUFFER_SIZE]; + int size = 0; + int id = 0; + + while (!thread_should_exit) { + if (read_data(uart, &id) == OK) { + switch (id) { + case ELECTRIC_AIR_MODULE: + build_eam_response(buffer, &size); + break; + + default: + continue; // Not a module we support. + } + + send_data(uart, buffer, size); + } + } + + INFO_MSG("exiting"); + + close(uart); + + thread_running = false; + + return 0; +} + +/** + * Process command line arguments and tart the daemon. + */ +int hott_telemetry_main(int argc, char *argv[]) +{ + if (argc < 1) { + ERROR_MSG("missing command"); + ERROR_MSG(commandline_usage); + exit(1); + } + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + INFO_MSG("deamon already running"); + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn("hott_telemetry", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 40, + 2048, + hott_telemetry_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + INFO_MSG("daemon is running"); + + } else { + INFO_MSG("daemon not started"); + } + + exit(0); + } + + ERROR_MSG("unrecognized command"); + ERROR_MSG(commandline_usage); + exit(1); +} + + + diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c new file mode 100644 index 0000000000..8bfb997737 --- /dev/null +++ b/apps/hott_telemetry/messages.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Author: @author Simon Wilks + * + * 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 messages.c + * + */ + +#include "messages.h" + +#include +#include +#include +#include +#include + +static int battery_sub = -1; +static int sensor_sub = -1; + +void messages_init(void) +{ + battery_sub = orb_subscribe(ORB_ID(battery_status)); + sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); +} + +void build_eam_response(uint8_t *buffer, int *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 battery_status_s battery; + memset(&battery, 0, sizeof(battery)); + orb_copy(ORB_ID(battery_status), battery_sub, &battery); + + struct eam_module_msg msg; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.start = START_BYTE; + msg.eam_sensor_id = ELECTRIC_AIR_MODULE; + msg.sensor_id = EAM_SENSOR_ID; + msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); + msg.temperature2 = TEMP_ZERO_CELSIUS; + 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; + + msg.stop = STOP_BYTE; + + memcpy(buffer, &msg, *size); +} \ No newline at end of file diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h new file mode 100644 index 0000000000..44001e04f0 --- /dev/null +++ b/apps/hott_telemetry/messages.h @@ -0,0 +1,123 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Author: @author Simon Wilks + * + * 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 messages.h + * + * Graupner HoTT Telemetry message generation. + * + */ +#ifndef MESSAGES_H_ +#define MESSAGES_H + +#include + +/* 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. + */ +#define POST_READ_DELAY_IN_USECS 4000 +/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower + * values can be used in practise though. + */ +#define POST_WRITE_DELAY_IN_USECS 2000 + +// Protocol constants. +#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request. +#define START_BYTE 0x7c +#define STOP_BYTE 0x7d +#define TEMP_ZERO_CELSIUS 0x14 + +/* Electric Air Module (EAM) constants. */ +#define ELECTRIC_AIR_MODULE 0x8e +#define EAM_SENSOR_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 warning; + 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 cell2_L; + uint8_t cell3_L; + uint8_t cell4_L; + uint8_t cell5_L; + uint8_t cell6_L; + uint8_t cell7_L; + uint8_t cell1_H; + uint8_t cell2_H; + uint8_t cell3_H; + uint8_t cell4_H; + uint8_t cell5_H; + uint8_t cell6_H; + uint8_t cell7_H; + uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */ + 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 temperature2; + 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_H; + 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_H; + 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 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 speed_H; + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ +}; + +void messages_init(void); +void build_eam_response(uint8_t *buffer, int *size); + +#endif /* MESSAGES_H_ */ diff --git a/apps/px4/tests/test_hott_telemetry.c b/apps/px4/tests/test_hott_telemetry.c new file mode 100644 index 0000000000..74aa0e614f --- /dev/null +++ b/apps/px4/tests/test_hott_telemetry.c @@ -0,0 +1,239 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Author: @author Simon Wilks + * + * 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 test_hott_telemetry.c + * + * Tests the Graupner HoTT telemetry support. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "tests.h" + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +static int open_uart(const char *device) +{ + /* baud rate */ + int speed = B19200; + + /* open uart */ + int uart = open(device, O_RDWR | O_NOCTTY); + + if (uart < 0) { + errx(1, "FAIL: Error opening port"); + return ERROR; + } + + /* Try to set baud rate */ + struct termios uart_config; + + /* Fill the struct for the new configuration */ + tcgetattr(uart, &uart_config); + + /* Clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* Set baud rate */ + if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { + errx(1, "FAIL: Error setting baudrate / termios config for cfsetispeed, cfsetospeed"); + return ERROR; + } + + if (tcsetattr(uart, TCSANOW, &uart_config) < 0) { + errx(1, "FAIL: Error setting baudrate / termios config for tcsetattr"); + return ERROR; + } + + return uart; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: test_hott_telemetry + ****************************************************************************/ + +int test_hott_telemetry(int argc, char *argv[]) +{ + warnx("HoTT Telemetry Test Requirements:"); + warnx("- Radio on and Electric Air. Mod on (telemetry -> sensor select)."); + warnx("- Receiver telemetry port must be in telemetry mode."); + warnx("- Connect telemetry wire to /dev/ttyS1 (USART2)."); + warnx("Testing..."); + + const char device[] = "/dev/ttyS1"; + int fd = open_uart(device); + + if (fd < 0) { + close(fd); + return ERROR; + } + + /* Activate single wire mode */ + ioctl(fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); + + char send = 'a'; + write(fd, &send, 1); + + /* Since TX and RX are now connected we should be able to read in what we wrote */ + const int timeout = 1000; + struct pollfd fds[] = { { .fd = fd, .events = POLLIN } }; + + if (poll(fds, 1, timeout) == 0) { + errx(1, "FAIL: Could not read sent data."); + } + + char receive; + read(fd, &receive, 1); + warnx("PASS: Single wire enabled. Sent %x and received %x", send, receive); + + + /* Attempt to read HoTT poll messages from the HoTT receiver */ + int received_count = 0; + int valid_count = 0; + const int max_polls = 5; + uint8_t byte; + + for (; received_count < 5; received_count++) { + if (poll(fds, 1, timeout) == 0) { + errx(1, "FAIL: Could not read sent data. Is your HoTT receiver plugged in on %s?", device); + break; + + } else { + read(fd, &byte, 1); + + if (byte == 0x80) { + valid_count++; + } + + /* Read the device ID being polled */ + read(fd, &byte, 1); + } + } + + if (received_count > 0 && valid_count > 0) { + if (received_count == max_polls && valid_count == max_polls) { + warnx("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls); + + } else { + warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count, max_polls, valid_count); + } + + } else { + /* Let's work out what went wrong */ + if (received_count == 0) { + errx(1, "FAIL: Could not read any polls from HoTT receiver device."); + } + + if (valid_count == 0) { + errx(1, "FAIL: Received unexpected values from the HoTT receiver device."); + } + } + + + /* Attempt to send a HoTT response messages */ + uint8_t response[] = {0x7c, 0x8e, 0x00, 0xe0, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf4, 0x01, 0x00, 0x00, \ + 0x19, 0x00, 0x00, 0x00, 0x30, 0x75, 0x78, 0x00, 0x00, 0x00, \ + 0x00, 0x00, 0x00, 0x7d, 0x12 + }; + + usleep(5000); + + for (unsigned int i = 0; i < sizeof(response); i++) { + write(fd, &response[i], 1); + usleep(1000); + } + + warnx("PASS: Response sent to the HoTT receiver device. Voltage should now show 2.5V."); + + + /* Disable single wire */ + ioctl(fd, TIOCSSINGLEWIRE, ~SER_SINGLEWIRE_ENABLED); + + write(fd, &send, 1); + + /* We should timeout as there will be nothing to read (TX and RX no longer connected) */ + if (poll(fds, 1, timeout) == 0) { + errx(1, "FAIL: timeout expected."); + } + + warnx("PASS: Single wire disabled."); + + close(fd); + exit(0); +} diff --git a/apps/px4/tests/tests.h b/apps/px4/tests/tests.h index 46450d10bf..cc3f5493a8 100644 --- a/apps/px4/tests/tests.h +++ b/apps/px4/tests/tests.h @@ -93,6 +93,7 @@ extern int test_uart_send(int argc, char *argv[]); extern int test_sleep(int argc, char *argv[]); extern int test_time(int argc, char *argv[]); extern int test_uart_console(int argc, char *argv[]); +extern int test_hott_telemetry(int argc, char *argv[]); extern int test_jig_voltages(int argc, char *argv[]); extern int test_param(int argc, char *argv[]); extern int test_bson(int argc, char *argv[]); diff --git a/apps/px4/tests/tests_main.c b/apps/px4/tests/tests_main.c index 5bedd257b5..ad6828f201 100644 --- a/apps/px4/tests/tests_main.c +++ b/apps/px4/tests/tests_main.c @@ -100,6 +100,7 @@ const struct { {"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST | OPT_NOALLTEST}, {"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST}, {"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST}, {"tone", test_tone, 0}, {"sleep", test_sleep, OPT_NOJIGTEST}, {"time", test_time, OPT_NOJIGTEST}, diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 5a85a8877d..a03d1d3dc0 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -92,6 +92,7 @@ CONFIGURED_APPS += fixedwing_att_control CONFIGURED_APPS += fixedwing_pos_control CONFIGURED_APPS += position_estimator CONFIGURED_APPS += attitude_estimator_ekf +CONFIGURED_APPS += hott_telemetry # Hacking tools #CONFIGURED_APPS += system/i2c diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 696d19a6c8..fd783dec5d 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -200,6 +200,12 @@ CONFIG_STM32_TIM9=y CONFIG_STM32_TIM10=y CONFIG_STM32_TIM11=y +# +# Enable single wire support. If this is not defined, then this mode cannot +# be enabled. +# +CONFIG_STM32_USART_SINGLEWIRE=y + # # We want the flash prefetch on for max performance. #