aboutsummaryrefslogtreecommitdiff
path: root/apps/hott_telemetry
diff options
context:
space:
mode:
authorSimon Wilks <sjwilks@gmail.com>2012-11-21 23:37:20 +0100
committerSimon Wilks <sjwilks@gmail.com>2012-11-21 23:37:20 +0100
commit054c65535f41c788a6db2accf1f920eaf3d05ff4 (patch)
treea31ecb50eec303cc95e74568fc75e3fe73b1f428 /apps/hott_telemetry
parent4a509684a79663b54717ffbc2c493752f069834f (diff)
downloadpx4-firmware-054c65535f41c788a6db2accf1f920eaf3d05ff4.tar.gz
px4-firmware-054c65535f41c788a6db2accf1f920eaf3d05ff4.tar.bz2
px4-firmware-054c65535f41c788a6db2accf1f920eaf3d05ff4.zip
General code cleanup.
Diffstat (limited to 'apps/hott_telemetry')
-rw-r--r--apps/hott_telemetry/hott_telemetry_main.c193
-rw-r--r--apps/hott_telemetry/messages.h9
2 files changed, 111 insertions, 91 deletions
diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c
index c5932baeb..00b8f8d66 100644
--- a/apps/hott_telemetry/hott_telemetry_main.c
+++ b/apps/hott_telemetry/hott_telemetry_main.c
@@ -39,6 +39,15 @@
*
* The HoTT receiver polls each device at a regular interval at which point
* a data packet can be returned if necessary.
+ *
+ * NOTE: Since HoTT telemetry works half-duplex over a single wire the wire
+ * is connected to both the UART TX and RX port. In order to send and receive
+ * we need to be able to disable one of these ports at a time. This level of
+ * control is currently not provided by Nuttx (yet) so we need to do this
+ * at the hardware level for now.
+ *
+ * TODO: Add support for at least the vario and GPS sensors.
+ *
*/
#include <fcntl.h>
@@ -53,7 +62,7 @@
#include "messages.h"
-// The following are equired for UART direct manipulation.
+/* The following are equired for UART direct manipulation. */
#include <arch/board/board.h>
#include "up_arch.h"
#include "chip.h"
@@ -62,7 +71,7 @@
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 uint32_t uart_addr; /**< The regsitry address of the UART for direct access */
/**
* Deamon management function.
*/
@@ -77,6 +86,7 @@ static int read_data(int uart);
static int send_data(int uart, const struct eam_module_msg *msg);
static void uart_disable_rx(void);
static void uart_disable_tx(void);
+static uint32_t get_uart_address(const char *device);
static int open_uart(const char *uart_name, struct termios *uart_config_original)
{
@@ -125,14 +135,100 @@ static int open_uart(const char *uart_name, struct termios *uart_config_original
return uart;
}
+int read_data(int uart)
+{
+ uart_disable_tx();
+
+ const int timeout = 1000;
+ struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
+
+ if (poll(fds, 1, timeout) > 0) {
+ /* get the mode: binary or text */
+ char mode;
+ read(uart, &mode, 1);
+
+ /* read the poll ID (device ID being targetted) */
+ char id;
+ read(uart, &id, 1);
+
+ /* if we have a binary mode request for our sensor ID let's run with it. */
+ if (mode != BINARY_MODE_REQUEST_ID || id != ELECTRIC_AIR_MODULE) {
+ return ERROR; // not really an error, rather uninteresting.
+ }
+ } else {
+ printf("Timeout\n");
+ return ERROR;
+ }
+ return OK;
+}
+
+int send_data(int uart, const struct eam_module_msg *msg)
+{
+ usleep(POST_READ_DELAY_IN_USECS);
+
+ uart_disable_rx();
+
+ uint16_t checksum = 0;
+ int size = sizeof(*msg);
+ char buffer[size];
+
+ memcpy(buffer, msg, size);
+
+ 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);
+ }
+
+ return OK;
+}
+
+void uart_disable_rx(void)
+{
+ uint32_t cr;
+ cr = getreg32(uart_addr);
+ cr &= ~(USART_CR1_RE); // turn off RX
+ cr |= (USART_CR1_TE); // turn on TX
+ putreg32(cr, uart_addr);
+}
+
+void uart_disable_tx(void)
+{
+ uint32_t cr;
+ cr = getreg32(uart_addr);
+ cr |= (USART_CR1_RE); // turn on RX
+ cr &= ~(USART_CR1_TE); // turn off TX
+ putreg32(cr, uart_addr);
+}
+
+uint32_t get_uart_address(const char *device)
+{
+ /* Map the tty device number to the UART address */
+ switch(device[strlen(device) - 1]) {
+ case '0': return STM32_USART1_CR1;
+ case '1': return STM32_USART2_CR1;
+ case '2': return STM32_UART5_CR1;
+ case '3': return STM32_USART6_CR1;
+ default: return STM32_UART5_CR1;
+ }
+}
+
int hott_telemetry_thread_main(int argc, char *argv[])
{
printf("[hott_telemetry] starting\n");
thread_running = true;
- char *device = "/dev/ttyS2"; // UART5
char *commandline_usage = "\tusage: hott_telemetry start|status|stop [-d device]\n";
+ char *device = "/dev/ttyS2"; /**< Default telemetry port: UART5 */
/* read commandline arguments */
for (int i = 0; i < argc && argv[i]; i++) {
@@ -157,6 +253,11 @@ int hott_telemetry_thread_main(int argc, char *argv[])
exit(ERROR);
}
+ /* Since we need to enable/disable both TX and RX on the UART at the device level
+ * we need to know the register address of the UART we are working with. Making it
+ * global so it's easy to remove later when TX/RX control is provided by Nuttx. */
+ uart_addr = get_uart_address(device);
+
messages_init();
struct eam_module_msg msg;
@@ -169,7 +270,6 @@ int hott_telemetry_thread_main(int argc, char *argv[])
printf("[hott_telemetry] exiting.\n");
- /* close uarts */
close(uart);
thread_running = false;
@@ -187,12 +287,7 @@ usage(const char *reason)
}
/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
+ * Process command line arguments and tart the daemon.
*/
int hott_telemetry_main(int argc, char *argv[])
{
@@ -210,7 +305,7 @@ int hott_telemetry_main(int argc, char *argv[])
thread_should_exit = false;
deamon_task = task_spawn("hott_telemetry",
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 20,
+ SCHED_PRIORITY_MAX - 40,
2048,
hott_telemetry_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -235,81 +330,5 @@ int hott_telemetry_main(int argc, char *argv[])
exit(1);
}
-int read_data(int uart)
-{
- uart_disable_tx();
-
- const int timeout = 1000;
- struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
-
- if (poll(fds, 1, timeout) > 0) {
- // get the mode: binary or text
- char mode;
- read(uart, &mode, 1);
-
- // read the poll ID (device ID being targetted)
- char id;
- read(uart, &id, 1);
-
- //printf("Reading: mode='%x' id='%x'\n", mode, id);
-
- // if we have a binary mode request for our sensor ID let's run with it
- if (mode != BINARY_MODE_REQUEST_ID || id != ELECTRIC_AIR_MODULE) {
- return ERROR; // not really an error, rather uninteresting.
- }
- } else {
- printf("Timeout\n");
- return ERROR;
- }
- return OK;
-}
-
-int send_data(int uart, const struct eam_module_msg *msg)
-{
- usleep(POST_READ_DELAY_IN_USECS);
-
- uart_disable_rx();
-
- uint16_t checksum = 0;
- int size = sizeof(*msg);
- char buffer[size];
-
- memcpy(buffer, msg, size);
-
- 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];
- }
-
- //printf("%x ", buffer[i]);
- write(uart, &buffer[i], 1);
-
- // Sleep before sending the next uint8_t.
- usleep(POST_WRITE_DELAY_IN_USECS);
- }
-
- return OK;
-}
-
-void uart_disable_rx()
-{
- uint32_t cr;
- cr = getreg32(STM32_UART5_CR1);
- cr &= ~(USART_CR1_RE); // turn off RX
- cr |= (USART_CR1_TE); // turn on TX
- putreg32(cr, STM32_UART5_CR1);
-}
-
-void uart_disable_tx()
-{
- uint32_t cr;
- cr = getreg32(STM32_UART5_CR1);
- cr |= (USART_CR1_RE); // turn on RX
- cr &= ~(USART_CR1_TE); // turn off TX
- putreg32(cr, STM32_UART5_CR1);
-}
diff --git a/apps/hott_telemetry/messages.h b/apps/hott_telemetry/messages.h
index 562010a06..fb305cd8d 100644
--- a/apps/hott_telemetry/messages.h
+++ b/apps/hott_telemetry/messages.h
@@ -43,10 +43,10 @@
#include <stdlib.h>
-// The HoTT receiver demands a minimum 5ms period of silence after delivering its request.
+/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request. */
#define POST_READ_DELAY_IN_USECS 4500
-// 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.
+/* 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 1500
// Protocol constants.
@@ -55,10 +55,11 @@
#define STOP_BYTE 0x7d
#define TEMP_ZERO_CELSIUS 0x14
-// Electric Air Module (EAM) constants.
+/* 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 */