forked from mavlink-router/mavlink-router
-
Notifications
You must be signed in to change notification settings - Fork 0
/
endpoint.h
198 lines (161 loc) · 4.76 KB
/
endpoint.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
/*
* This file is part of the MAVLink Router project
*
* Copyright (C) 2016 Intel Corporation. All rights reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#pragma once
#include <mavlink.h>
#include <memory>
#include <vector>
#include "comm.h"
#include "pollable.h"
#include "timeout.h"
class Mainloop;
/*
* mavlink 2.0 packet in its wire format
*
* Packet size:
* sizeof(mavlink_router_mavlink2_header)
* + payload length
* + 2 (checksum)
* + signature (0 if not signed)
*/
struct _packed_ mavlink_router_mavlink2_header {
uint8_t magic;
uint8_t payload_len;
uint8_t incompat_flags;
uint8_t compat_flags;
uint8_t seq;
uint8_t sysid;
uint8_t compid;
uint32_t msgid : 24;
};
/*
* mavlink 1.0 packet in its wire format
*
* Packet size:
* sizeof(mavlink_router_mavlink1_header)
* + payload length
* + 2 (checksum)
*/
struct _packed_ mavlink_router_mavlink1_header {
uint8_t magic;
uint8_t payload_len;
uint8_t seq;
uint8_t sysid;
uint8_t compid;
uint8_t msgid;
};
class Endpoint : public Pollable {
public:
/*
* Success returns for @read_msg()
*/
enum read_msg_result {
ReadOk = 1,
ReadUnkownMsg,
};
Endpoint(const char *name, bool crc_check_enabled);
virtual ~Endpoint();
int handle_read() override;
bool handle_canwrite() override;
void print_statistics();
virtual int write_msg(const struct buffer *pbuf) = 0;
virtual int flush_pending_msgs() = 0;
void log_aggregate(unsigned int interval_sec);
uint8_t get_trimmed_zeros(const struct buffer *buffer);
uint8_t get_system_id() { return _system_id; }
struct buffer rx_buf;
struct buffer tx_buf;
protected:
virtual int read_msg(struct buffer *pbuf, int *target_system);
virtual ssize_t _read_msg(uint8_t *buf, size_t len) = 0;
bool _check_crc(const mavlink_msg_entry_t *msg_entry);
const char *_name;
size_t _last_packet_len = 0;
// Statistics
struct {
struct {
uint64_t crc_error_bytes = 0;
uint64_t handled_bytes = 0;
uint32_t total = 0; // handled + crc error + seq lost
uint32_t crc_error = 0;
uint32_t handled = 0;
uint32_t drop_seq_total = 0;
uint8_t expected_seq = 0;
} read;
struct {
uint64_t bytes = 0;
uint32_t total = 0;
} write;
} _stat;
const bool _crc_check_enabled;
uint32_t _incomplete_msgs = 0;
uint8_t _system_id = 0;
};
class UartEndpoint : public Endpoint {
public:
UartEndpoint() : Endpoint{"UART", true} { }
virtual ~UartEndpoint();
int write_msg(const struct buffer *pbuf) override;
int flush_pending_msgs() override { return -ENOSYS; }
int open(const char *path);
int set_speed(speed_t baudrate);
int add_speeds(std::vector<unsigned long> baudrates);
protected:
int read_msg(struct buffer *pbuf, int *target_sysid) override;
ssize_t _read_msg(uint8_t *buf, size_t len) override;
private:
size_t _current_baud_idx = 0;
Timeout *_change_baud_timeout = nullptr;
std::vector<unsigned long> _baudrates;
bool _change_baud_cb(void *data);
};
class UdpEndpoint : public Endpoint {
public:
UdpEndpoint();
virtual ~UdpEndpoint() { }
int write_msg(const struct buffer *pbuf) override;
int flush_pending_msgs() override { return -ENOSYS; }
int open(const char *ip, unsigned long port, bool bind = false);
struct sockaddr_in sockaddr;
protected:
ssize_t _read_msg(uint8_t *buf, size_t len) override;
};
class TcpEndpoint : public Endpoint {
public:
TcpEndpoint();
~TcpEndpoint();
int accept(int listener_fd);
int open(const char *ip, unsigned long port);
void close();
int write_msg(const struct buffer *pbuf) override;
int flush_pending_msgs() override { return -ENOSYS; }
struct sockaddr_in sockaddr;
int retry_timeout = 0;
inline const char *get_ip() {
return _ip;
}
inline unsigned long get_port() {
return _port;
}
bool is_valid() override { return _valid; };
protected:
ssize_t _read_msg(uint8_t *buf, size_t len) override;
private:
char *_ip = nullptr;
unsigned long _port = 0;
bool _valid = true;
};