aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorSimon Wilks <sjwilks@gmail.com>2013-07-13 22:18:52 +0200
committerSimon Wilks <sjwilks@gmail.com>2013-07-13 22:18:52 +0200
commit9aa25c5671b6966111dd75687945a8a0b3c8fa19 (patch)
tree52b8179ae8415bf27acd39608e36df459b1efaf9 /src/drivers
parentfa29694f0ba85c0b140dc460be14a5205da9c093 (diff)
downloadpx4-firmware-9aa25c5671b6966111dd75687945a8a0b3c8fa19.tar.gz
px4-firmware-9aa25c5671b6966111dd75687945a8a0b3c8fa19.tar.bz2
px4-firmware-9aa25c5671b6966111dd75687945a8a0b3c8fa19.zip
Remove unused code.
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/hott/comms.cpp5
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp37
-rw-r--r--src/drivers/hott/messages.cpp3
4 files changed, 3 insertions, 44 deletions
diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp
index 1da1c5c18..cb8bbba37 100644
--- a/src/drivers/hott/comms.cpp
+++ b/src/drivers/hott/comms.cpp
@@ -40,15 +40,10 @@
#include "comms.h"
#include <fcntl.h>
-#include <nuttx/config.h>
-#include <stdlib.h>
#include <stdio.h>
-#include <string.h>
#include <sys/ioctl.h>
#include <systemlib/err.h>
-#include <systemlib/systemlib.h>
#include <termios.h>
-#include <unistd.h>
int
open_uart(const char *device)
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index ad7e74e62..ada7f9fb7 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -55,7 +55,7 @@
#include "../comms.h"
#include "../messages.h"
-#define DEFAULT_UART "/dev/ttyS2"; /**< USART5 */
+#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
/* Oddly, ERROR is not defined for C++ */
#ifdef ERROR
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index 1c68e06b1..042d9f816 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -57,7 +57,7 @@
#include "../comms.h"
#include "../messages.h"
-#define DEFAULT_UART "/dev/ttyS1"; /**< USART2 */
+#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
/* Oddly, ERROR is not defined for C++ */
#ifdef ERROR
@@ -115,41 +115,6 @@ recv_req_id(int uart, uint8_t *id)
}
int
-recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id)
-{
- usleep(5000);
-
- static const int timeout_ms = 1000;
-
- struct pollfd fds;
- fds.fd = uart;
- fds.events = POLLIN;
-
- // XXX should this poll be inside the while loop???
- if (poll(&fds, 1, timeout_ms) > 0) {
- int i = 0;
- bool stop_byte_read = false;
- while (true) {
- read(uart, &buffer[i], sizeof(buffer[i]));
- //printf("[%d]: %d\n", i, buffer[i]);
-
- if (stop_byte_read) {
- // process checksum
- *size = ++i;
- return OK;
- }
- // XXX can some other field not have the STOP BYTE value?
- if (buffer[i] == STOP_BYTE) {
- *id = buffer[1];
- stop_byte_read = true;
- }
- i++;
- }
- }
- return ERROR;
-}
-
-int
send_data(int uart, uint8_t *buffer, size_t size)
{
usleep(POST_READ_DELAY_IN_USECS);
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index c5d73ab11..57c256339 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -61,10 +61,9 @@ static int _sensor_sub = -1;
static int _airspeed_sub = -1;
static int _esc_sub = -1;
-orb_advert_t _esc_pub;
+static orb_advert_t _esc_pub;
struct esc_status_s _esc;
-
static bool _home_position_set = false;
static double _home_lat = 0.0d;
static double _home_lon = 0.0d;