AP_HAL_Linux: add prototype for handling SoloLink

This allows to use a Solo controller to control Linux-based flight
controllers. The protocol has been derived by analyzing a tcpdump
trace: some fields are ignored. Example trace of RC data (obtained
with `tshark -T fields -e data -n -c 5 -r  rc.pcap`

 unkonwn              seq   ch1  ch2  ch3  ...                ch8
 5fa8 f441 3414 0500 73d7  dc05 dc05 dc05 db05 e803 e803 e803 f401
 73f6 f441 3414 0500 74d7  dc05 dc05 dc05 db05 e803 e803 e803 f401
 dc44 f541 3414 0500 75d7  dc05 dc05 dc05 db05 e803 e803 e803 f401
 bc92 f541 3414 0500 76d7  dc05 dc05 dc05 db05 e803 e803 e803 f401
 dfe0 f541 3414 0500 77d7  dc05 dc05 dc05 db05 e803 e803 e803 f401
This commit is contained in:
Lucas De Marchi 2017-05-26 14:58:04 -07:00
parent 8c8fe4b1bb
commit 79b004cf6a
2 changed files with 166 additions and 0 deletions

View File

@ -0,0 +1,106 @@
/*
* Copyright (C) 2017 Intel Corporation. All rights reserved.
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "RCInput_SoloLink.h"
#include <errno.h>
#include <inttypes.h>
#include <stdio.h>
#include <AP_HAL/AP_HAL.h>
#define DEBUG 0
#if DEBUG
#define debug(fmt, args...) ::printf(fmt "\n", ##args)
#else
#define debug(fmt, args...)
#endif
extern const AP_HAL::HAL& hal;
using namespace Linux;
RCInput_SoloLink::RCInput_SoloLink()
{
memset(&_packet, 0, sizeof(_packet));
}
void RCInput_SoloLink::init()
{
if (!_socket.bind("0.0.0.0", PORT)) {
AP_HAL::panic("failed to bind UDP socket");
}
// timeout is handled by poll() in SocketAPM
_socket.set_blocking(true);
return;
}
bool RCInput_SoloLink::_check_hdr(ssize_t len)
{
if (len < (ssize_t) sizeof(_packet)) {
hal.console->printf("RCInput: Packet too small (%zd), doesn't contain full frame\n",
len);
return false;
}
uint64_t now_usec = AP_HAL::micros64();
uint64_t delay = now_usec - _last_usec;
if (_last_usec != 0 && delay > 40000) {
debug("RCInput: no rc cmds received for %llu\n", (unsigned long long)delay);
}
_last_usec = now_usec;
uint16_t seq = le16toh(_packet.seq);
if (seq - _last_seq > 1) {
debug("RCInput: gap in rc cmds : %u\n", seq - _last_seq);
}
_last_seq = seq;
return true;
}
/* TODO: this should be a PollerThread or at least stop using a SchedThread */
void RCInput_SoloLink::_timer_tick(void)
{
do {
uint16_t channels[8];
ssize_t r;
r = _socket.recv(&_packet.buf, sizeof(_packet), 20);
if (r < 0) {
break;
}
if (!_check_hdr(r)) {
break;
}
channels[0] = le16toh(_packet.channel[1]);
channels[1] = le16toh(_packet.channel[2]);
channels[2] = le16toh(_packet.channel[0]);
for (unsigned int i = 3; i < 8; i++) {
channels[i] = le16toh(_packet.channel[i]);
}
_update_periods(channels, 8);
} while (true);
}

View File

@ -0,0 +1,60 @@
/*
* Copyright (C) 2017 Intel Corporation. All rights reserved.
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <unistd.h>
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/sparse-endian.h>
#include "RCInput.h"
namespace Linux {
class RCInput_SoloLink : public RCInput
{
public:
RCInput_SoloLink();
void init();
void _timer_tick();
private:
static const unsigned int PACKET_LEN = 26;
static const unsigned int PORT = 5005;
union packet {
struct PACKED {
/* changes at every packet */
uint32_t _unknown0;
/* apparently doesn't change: version? */
uint32_t _unknown1;
le16_t seq;
le16_t channel[8];
};
uint8_t buf[PACKET_LEN];
};
bool _check_hdr(ssize_t len);
SocketAPM _socket{true};
uint64_t _last_usec = 0;
uint16_t _last_seq = 0;
union packet _packet;
};
}