forked from Archive/PX4-Autopilot
Remove unused code.
This commit is contained in:
parent
fa29694f0b
commit
9aa25c5671
|
@ -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)
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
@ -114,41 +114,6 @@ recv_req_id(int uart, uint8_t *id)
|
|||
return OK;
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue