ardupilot/libraries/AP_HAL_Linux/RCInput_SoloLink.h
Lucas De Marchi 66a1e420cb AP_HAL_Linux: RCInput_SoloLink: better name to first field
Checking the time on the tcpdump capture, it matches the first fields
from the data:

$ tshark -n -c 4 -r  ~/tmp/solo/rc.pcap
    1   0.000000     10.1.1.1 → 10.1.1.10    UDP 68 5005 → 5005 Len=26
    2   0.019976     10.1.1.1 → 10.1.1.10    UDP 68 5005 → 5005 Len=26
    3   0.040046     10.1.1.1 → 10.1.1.10    UDP 68 5005 → 5005 Len=26
    4   0.059961     10.1.1.1 → 10.1.1.10    UDP 68 5005 → 5005 Len=26

From the previous commit (first 2 packets):

     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

0x0005143441f45fa8 - 0x0005143441f4f673 = 0x4E14 = 19988 (usec)

Which seems to approximately match for the other packets as well. We are
not using the field since we rather get the time when we receive it, but
at least use a better name.
2017-08-17 12:04:27 -07:00

58 lines
1.4 KiB
C++

/*
* 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 {
uint64_t timestamp_usec;
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;
};
}