|
|
|
@ -54,6 +54,7 @@
@@ -54,6 +54,7 @@
|
|
|
|
|
|
|
|
|
|
#include "RCOutput_Tap.h" |
|
|
|
|
|
|
|
|
|
#include <errno.h> |
|
|
|
|
#include <fcntl.h> |
|
|
|
|
#include <stdio.h> |
|
|
|
|
#include <sys/stat.h> |
|
|
|
@ -61,8 +62,6 @@
@@ -61,8 +62,6 @@
|
|
|
|
|
#include <termios.h> |
|
|
|
|
#include <unistd.h> |
|
|
|
|
|
|
|
|
|
#include <drivers/drv_hrt.h> |
|
|
|
|
|
|
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
|
|
|
|
|
|
#define DEBUG 0 |
|
|
|
@ -79,7 +78,6 @@ extern const AP_HAL::HAL &hal;
@@ -79,7 +78,6 @@ extern const AP_HAL::HAL &hal;
|
|
|
|
|
/****** ESC data types ******/ |
|
|
|
|
|
|
|
|
|
#define ESC_HAVE_CURRENT_SENSOR |
|
|
|
|
#define MIN_BOOT_TIME_USEC (550 * AP_USEC_PER_MSEC) |
|
|
|
|
|
|
|
|
|
static const uint8_t crcTable[256] = { |
|
|
|
|
0x00, 0xE7, 0x29, 0xCE, 0x52, 0xB5, 0x7B, 0x9C, 0xA4, 0x43, 0x8D, 0x6A, |
|
|
|
@ -137,7 +135,7 @@ static const uint8_t device_dir_map[] = {0, 1, 0, 1, 0, 1, 0, 1};
@@ -137,7 +135,7 @@ static const uint8_t device_dir_map[] = {0, 1, 0, 1, 0, 1, 0, 1};
|
|
|
|
|
|
|
|
|
|
#define MIN_BOOT_TIME_MSEC (550) // Minimum time to wait after Power on before sending commands
|
|
|
|
|
|
|
|
|
|
namespace PX4 { |
|
|
|
|
namespace ap { |
|
|
|
|
|
|
|
|
|
/****** Run ***********/ |
|
|
|
|
|
|
|
|
@ -304,7 +302,7 @@ enum PARSR_ESC_STATE {
@@ -304,7 +302,7 @@ enum PARSR_ESC_STATE {
|
|
|
|
|
/****************************/ |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
using namespace PX4; |
|
|
|
|
using namespace ap; |
|
|
|
|
|
|
|
|
|
void RCOutput_Tap::_uart_close() |
|
|
|
|
{ |
|
|
|
@ -322,7 +320,7 @@ bool RCOutput_Tap::_uart_open()
@@ -322,7 +320,7 @@ bool RCOutput_Tap::_uart_open()
|
|
|
|
|
int termios_state = -1; |
|
|
|
|
|
|
|
|
|
if (_uart_fd < 0) { |
|
|
|
|
PX4_ERR("failed to open uart device!"); |
|
|
|
|
::fprintf(stderr, "failed to open uart device! %s\n", UART_DEVICE_PATH); |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -353,16 +351,16 @@ bool RCOutput_Tap::_uart_open()
@@ -353,16 +351,16 @@ bool RCOutput_Tap::_uart_open()
|
|
|
|
|
|
|
|
|
|
void RCOutput_Tap::init() |
|
|
|
|
{ |
|
|
|
|
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout"); |
|
|
|
|
_perf_rcout = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "APM_rcout"); |
|
|
|
|
|
|
|
|
|
if (!_uart_open()) { |
|
|
|
|
AP_HAL::panic("Unable to open " UART_DEVICE_PATH); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
hrt_abstime uptime_usec = hrt_absolute_time(); |
|
|
|
|
if (uptime_usec < MIN_BOOT_TIME_USEC) { |
|
|
|
|
hal.scheduler->delay((MIN_BOOT_TIME_USEC - uptime_usec) / AP_USEC_PER_MSEC); |
|
|
|
|
uint32_t now = AP_HAL::millis(); |
|
|
|
|
if (now < MIN_BOOT_TIME_MSEC) { |
|
|
|
|
hal.scheduler->delay(MIN_BOOT_TIME_MSEC - now); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* Issue Basic Config */ |
|
|
|
@ -504,7 +502,7 @@ void RCOutput_Tap::push()
@@ -504,7 +502,7 @@ void RCOutput_Tap::push()
|
|
|
|
|
{ |
|
|
|
|
_corking = false; |
|
|
|
|
|
|
|
|
|
perf_begin(_perf_rcout); |
|
|
|
|
hal.util->perf_begin(_perf_rcout); |
|
|
|
|
|
|
|
|
|
uint16_t out[TAP_ESC_MAX_MOTOR_NUM]; |
|
|
|
|
uint8_t motor_cnt = _channels_count; |
|
|
|
@ -578,7 +576,7 @@ void RCOutput_Tap::push()
@@ -578,7 +576,7 @@ void RCOutput_Tap::push()
|
|
|
|
|
|
|
|
|
|
_next_channel_reply = (_next_channel_reply + 1) % _channels_count; |
|
|
|
|
|
|
|
|
|
perf_end(_perf_rcout); |
|
|
|
|
hal.util->perf_end(_perf_rcout); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif |