2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-03 06:30:35 -04:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include "RCInput.h"
|
2015-06-10 03:45:26 -03:00
|
|
|
#include <fcntl.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <drivers/drv_pwm_output.h>
|
2013-01-03 17:31:23 -04:00
|
|
|
#include <drivers/drv_hrt.h>
|
2013-01-26 21:51:34 -04:00
|
|
|
#include <uORB/uORB.h>
|
2013-01-03 06:30:35 -04:00
|
|
|
|
|
|
|
using namespace PX4;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-01-04 07:27:04 -04:00
|
|
|
void PX4RCInput::init(void* unused)
|
2013-01-03 06:30:35 -04:00
|
|
|
{
|
2013-01-26 21:51:34 -04:00
|
|
|
_perf_rcin = perf_alloc(PC_ELAPSED, "APM_rcin");
|
|
|
|
_rc_sub = orb_subscribe(ORB_ID(input_rc));
|
|
|
|
if (_rc_sub == -1) {
|
|
|
|
hal.scheduler->panic("Unable to subscribe to input_rc");
|
|
|
|
}
|
2013-01-03 17:31:23 -04:00
|
|
|
clear_overrides();
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_init(&rcin_mutex, NULL);
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
|
2014-03-25 00:39:41 -03:00
|
|
|
bool PX4RCInput::new_input()
|
2013-01-22 16:57:59 -04:00
|
|
|
{
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_lock(&rcin_mutex);
|
2014-03-07 16:43:52 -04:00
|
|
|
bool valid = _rcin.timestamp_last_signal != _last_read || _override_valid;
|
2015-02-08 18:57:02 -04:00
|
|
|
_last_read = _rcin.timestamp_last_signal;
|
|
|
|
_override_valid = false;
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
|
|
|
return valid;
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
|
2014-03-25 00:39:41 -03:00
|
|
|
uint8_t PX4RCInput::num_channels()
|
|
|
|
{
|
|
|
|
pthread_mutex_lock(&rcin_mutex);
|
|
|
|
uint8_t n = _rcin.channel_count;
|
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
|
|
|
return n;
|
|
|
|
}
|
|
|
|
|
2013-01-22 16:57:59 -04:00
|
|
|
uint16_t PX4RCInput::read(uint8_t ch)
|
|
|
|
{
|
2013-01-26 21:51:34 -04:00
|
|
|
if (ch >= RC_INPUT_MAX_CHANNELS) {
|
2013-01-03 17:31:23 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_lock(&rcin_mutex);
|
2013-01-03 17:31:23 -04:00
|
|
|
if (_override[ch]) {
|
2013-12-31 07:24:55 -04:00
|
|
|
uint16_t v = _override[ch];
|
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
|
|
|
return v;
|
2013-01-03 17:31:23 -04:00
|
|
|
}
|
2013-01-26 21:51:34 -04:00
|
|
|
if (ch >= _rcin.channel_count) {
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
|
|
|
return 0;
|
2013-01-26 21:51:34 -04:00
|
|
|
}
|
2013-12-31 07:24:55 -04:00
|
|
|
uint16_t v = _rcin.values[ch];
|
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
|
|
|
return v;
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
|
2013-01-22 16:57:59 -04:00
|
|
|
uint8_t PX4RCInput::read(uint16_t* periods, uint8_t len)
|
|
|
|
{
|
2013-01-26 21:51:34 -04:00
|
|
|
if (len > RC_INPUT_MAX_CHANNELS) {
|
|
|
|
len = RC_INPUT_MAX_CHANNELS;
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
for (uint8_t i = 0; i < len; i++){
|
|
|
|
periods[i] = read(i);
|
|
|
|
}
|
|
|
|
return len;
|
|
|
|
}
|
|
|
|
|
2013-01-22 16:57:59 -04:00
|
|
|
bool PX4RCInput::set_overrides(int16_t *overrides, uint8_t len)
|
|
|
|
{
|
2013-01-03 06:30:35 -04:00
|
|
|
bool res = false;
|
|
|
|
for (uint8_t i = 0; i < len; i++) {
|
|
|
|
res |= set_override(i, overrides[i]);
|
|
|
|
}
|
|
|
|
return res;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool PX4RCInput::set_override(uint8_t channel, int16_t override) {
|
|
|
|
if (override < 0) {
|
|
|
|
return false; /* -1: no change. */
|
|
|
|
}
|
2013-01-26 21:51:34 -04:00
|
|
|
if (channel >= RC_INPUT_MAX_CHANNELS) {
|
2013-01-22 16:57:59 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
_override[channel] = override;
|
|
|
|
if (override != 0) {
|
|
|
|
_override_valid = true;
|
|
|
|
return true;
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
void PX4RCInput::clear_overrides()
|
|
|
|
{
|
2013-01-26 21:51:34 -04:00
|
|
|
for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
|
2013-01-22 16:57:59 -04:00
|
|
|
set_override(i, 0);
|
2013-01-03 06:30:35 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-01-26 21:51:34 -04:00
|
|
|
void PX4RCInput::_timer_tick(void)
|
|
|
|
{
|
|
|
|
perf_begin(_perf_rcin);
|
|
|
|
bool rc_updated = false;
|
|
|
|
if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_lock(&rcin_mutex);
|
|
|
|
orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
|
|
|
|
pthread_mutex_unlock(&rcin_mutex);
|
2013-01-26 21:51:34 -04:00
|
|
|
}
|
2014-03-25 00:39:41 -03:00
|
|
|
// note, we rely on the vehicle code checking new_input()
|
2013-12-30 19:58:49 -04:00
|
|
|
// and a timeout for the last valid input to handle failsafe
|
2013-01-26 21:51:34 -04:00
|
|
|
perf_end(_perf_rcin);
|
|
|
|
}
|
|
|
|
|
2015-06-10 03:45:26 -03:00
|
|
|
bool PX4RCInput::rc_bind(int dsmMode)
|
|
|
|
{
|
|
|
|
int fd = open("/dev/px4io", 0);
|
|
|
|
if (fd == -1) {
|
|
|
|
hal.console->printf("RCInput: failed to open /dev/px4io\n");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t mode = (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES);
|
|
|
|
int ret = ioctl(fd, DSM_BIND_START, mode);
|
|
|
|
close(fd);
|
|
|
|
if (ret != 0) {
|
|
|
|
hal.console->printf("RCInput: Unable to start DSM bind\n");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2013-01-03 06:30:35 -04:00
|
|
|
#endif
|