forked from mavlink/c_uart_interface_example
-
Notifications
You must be signed in to change notification settings - Fork 0
/
serial_port.cpp
544 lines (453 loc) · 14.1 KB
/
serial_port.cpp
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
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
/****************************************************************************
*
* Copyright (c) 2014 MAVlink Development Team. All rights reserved.
* Author: Trent Lukaczyk, <[email protected]>
* Jaycee Lock, <[email protected]>
* Lorenz Meier, <[email protected]>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file serial_port.cpp
*
* @brief Serial interface functions
*
* Functions for opening, closing, reading and writing via serial ports
*
* @author Trent Lukaczyk, <[email protected]>
* @author Jaycee Lock, <[email protected]>
* @author Lorenz Meier, <[email protected]>
*
*/
// ------------------------------------------------------------------------------
// Includes
// ------------------------------------------------------------------------------
#include "serial_port.h"
// ----------------------------------------------------------------------------------
// Serial Port Manager Class
// ----------------------------------------------------------------------------------
// ------------------------------------------------------------------------------
// Con/De structors
// ------------------------------------------------------------------------------
Serial_Port::
Serial_Port(const char *uart_name_ , int baudrate_)
{
initialize_defaults();
uart_name = uart_name_;
baudrate = baudrate_;
}
Serial_Port::
Serial_Port()
{
initialize_defaults();
}
Serial_Port::
~Serial_Port()
{
// destroy mutex
pthread_mutex_destroy(&lock);
}
void
Serial_Port::
initialize_defaults()
{
// Initialize attributes
debug = false;
fd = -1;
status = SERIAL_PORT_CLOSED;
uart_name = (char*)"/dev/ttyUSB0";
baudrate = 57600;
// Start mutex
int result = pthread_mutex_init(&lock, NULL);
if ( result != 0 )
{
printf("\n mutex init failed\n");
throw 1;
}
}
// ------------------------------------------------------------------------------
// Read from Serial
// ------------------------------------------------------------------------------
int
Serial_Port::
read_message(mavlink_message_t &message)
{
uint8_t cp;
mavlink_status_t status;
uint8_t msgReceived = false;
// --------------------------------------------------------------------------
// READ FROM PORT
// --------------------------------------------------------------------------
// this function locks the port during read
int result = _read_port(cp);
// --------------------------------------------------------------------------
// PARSE MESSAGE
// --------------------------------------------------------------------------
if (result > 0)
{
// the parsing
msgReceived = mavlink_parse_char(MAVLINK_COMM_1, cp, &message, &status);
// check for dropped packets
if ( (lastStatus.packet_rx_drop_count != status.packet_rx_drop_count) && debug )
{
printf("ERROR: DROPPED %d PACKETS\n", status.packet_rx_drop_count);
unsigned char v=cp;
fprintf(stderr,"%02x ", v);
}
lastStatus = status;
}
// Couldn't read from port
else
{
fprintf(stderr, "ERROR: Could not read from fd %d\n", fd);
}
// --------------------------------------------------------------------------
// DEBUGGING REPORTS
// --------------------------------------------------------------------------
if(msgReceived && debug)
{
// Report info
printf("Received message from serial with ID #%d (sys:%d|comp:%d):\n", message.msgid, message.sysid, message.compid);
fprintf(stderr,"Received serial data: ");
unsigned int i;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// check message is write length
unsigned int messageLength = mavlink_msg_to_send_buffer(buffer, &message);
// message length error
if (messageLength > MAVLINK_MAX_PACKET_LEN)
{
fprintf(stderr, "\nFATAL ERROR: MESSAGE LENGTH IS LARGER THAN BUFFER SIZE\n");
}
// print out the buffer
else
{
for (i=0; i<messageLength; i++)
{
unsigned char v=buffer[i];
fprintf(stderr,"%02x ", v);
}
fprintf(stderr,"\n");
}
}
// Done!
return msgReceived;
}
// ------------------------------------------------------------------------------
// Write to Serial
// ------------------------------------------------------------------------------
int
Serial_Port::
write_message(const mavlink_message_t &message)
{
char buf[300];
// Translate message to buffer
unsigned len = mavlink_msg_to_send_buffer((uint8_t*)buf, &message);
// Write buffer to serial port, locks port while writing
int bytesWritten = _write_port(buf,len);
return bytesWritten;
}
// ------------------------------------------------------------------------------
// Open Serial Port
// ------------------------------------------------------------------------------
/**
* throws EXIT_FAILURE if could not open the port
*/
void
Serial_Port::
open_serial()
{
// --------------------------------------------------------------------------
// OPEN PORT
// --------------------------------------------------------------------------
printf("OPEN PORT\n");
fd = _open_port(uart_name);
// Check success
if (fd == -1)
{
printf("failure, could not open port.\n");
throw EXIT_FAILURE;
}
// --------------------------------------------------------------------------
// SETUP PORT
// --------------------------------------------------------------------------
bool success = _setup_port(baudrate, 8, 1, false, false);
// --------------------------------------------------------------------------
// CHECK STATUS
// --------------------------------------------------------------------------
if (!success)
{
printf("failure, could not configure port.\n");
throw EXIT_FAILURE;
}
if (fd <= 0)
{
printf("Connection attempt to port %s with %d baud, 8N1 failed, exiting.\n", uart_name, baudrate);
throw EXIT_FAILURE;
}
// --------------------------------------------------------------------------
// CONNECTED!
// --------------------------------------------------------------------------
printf("Connected to %s with %d baud, 8 data bits, no parity, 1 stop bit (8N1)\n", uart_name, baudrate);
lastStatus.packet_rx_drop_count = 0;
status = true;
printf("\n");
return;
}
// ------------------------------------------------------------------------------
// Close Serial Port
// ------------------------------------------------------------------------------
void
Serial_Port::
close_serial()
{
printf("CLOSE PORT\n");
int result = close(fd);
if ( result )
{
fprintf(stderr,"WARNING: Error on port close (%i)\n", result );
}
status = false;
printf("\n");
}
// ------------------------------------------------------------------------------
// Convenience Functions
// ------------------------------------------------------------------------------
void
Serial_Port::
start()
{
open_serial();
}
void
Serial_Port::
stop()
{
close_serial();
}
// ------------------------------------------------------------------------------
// Quit Handler
// ------------------------------------------------------------------------------
void
Serial_Port::
handle_quit( int sig )
{
try {
stop();
}
catch (int error) {
fprintf(stderr,"Warning, could not stop serial port\n");
}
}
// ------------------------------------------------------------------------------
// Helper Function - Open Serial Port File Descriptor
// ------------------------------------------------------------------------------
// Where the actual port opening happens, returns file descriptor 'fd'
int
Serial_Port::
_open_port(const char* port)
{
// Open serial port
// O_RDWR - Read and write
// O_NOCTTY - Ignore special chars like CTRL-C
fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
// Check for Errors
if (fd == -1)
{
/* Could not open the port. */
return(-1);
}
// Finalize
else
{
fcntl(fd, F_SETFL, 0);
}
// Done!
return fd;
}
// ------------------------------------------------------------------------------
// Helper Function - Setup Serial Port
// ------------------------------------------------------------------------------
// Sets configuration, flags, and baud rate
bool
Serial_Port::
_setup_port(int baud, int data_bits, int stop_bits, bool parity, bool hardware_control)
{
// Check file descriptor
if(!isatty(fd))
{
fprintf(stderr, "\nERROR: file descriptor %d is NOT a serial port\n", fd);
return false;
}
// Read file descritor configuration
struct termios config;
if(tcgetattr(fd, &config) < 0)
{
fprintf(stderr, "\nERROR: could not read configuration of fd %d\n", fd);
return false;
}
// Input flags - Turn off input processing
// convert break to null byte, no CR to NL translation,
// no NL to CR translation, don't mark parity errors or breaks
// no input parity check, don't strip high bit off,
// no XON/XOFF software flow control
config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
INLCR | PARMRK | INPCK | ISTRIP | IXON);
// Output flags - Turn off output processing
// no CR to NL translation, no NL to CR-NL translation,
// no NL to CR translation, no column 0 CR suppression,
// no Ctrl-D suppression, no fill characters, no case mapping,
// no local output processing
config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
ONOCR | OFILL | OPOST);
#ifdef OLCUC
config.c_oflag &= ~OLCUC;
#endif
#ifdef ONOEOT
config.c_oflag &= ~ONOEOT;
#endif
// No line processing:
// echo off, echo newline off, canonical mode off,
// extended input processing off, signal chars off
config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
// Turn off character processing
// clear current char size mask, no parity checking,
// no output processing, force 8 bit input
config.c_cflag &= ~(CSIZE | PARENB);
config.c_cflag |= CS8;
// One input byte is enough to return from read()
// Inter-character timer off
config.c_cc[VMIN] = 1;
config.c_cc[VTIME] = 10; // was 0
// Get the current options for the port
////struct termios options;
////tcgetattr(fd, &options);
// Apply baudrate
switch (baud)
{
case 1200:
if (cfsetispeed(&config, B1200) < 0 || cfsetospeed(&config, B1200) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
case 1800:
cfsetispeed(&config, B1800);
cfsetospeed(&config, B1800);
break;
case 9600:
cfsetispeed(&config, B9600);
cfsetospeed(&config, B9600);
break;
case 19200:
cfsetispeed(&config, B19200);
cfsetospeed(&config, B19200);
break;
case 38400:
if (cfsetispeed(&config, B38400) < 0 || cfsetospeed(&config, B38400) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
case 57600:
if (cfsetispeed(&config, B57600) < 0 || cfsetospeed(&config, B57600) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
case 115200:
if (cfsetispeed(&config, B115200) < 0 || cfsetospeed(&config, B115200) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
// These two non-standard (by the 70'ties ) rates are fully supported on
// current Debian and Mac OS versions (tested since 2010).
case 460800:
if (cfsetispeed(&config, B460800) < 0 || cfsetospeed(&config, B460800) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
case 921600:
if (cfsetispeed(&config, B921600) < 0 || cfsetospeed(&config, B921600) < 0)
{
fprintf(stderr, "\nERROR: Could not set desired baud rate of %d Baud\n", baud);
return false;
}
break;
default:
fprintf(stderr, "ERROR: Desired baud rate %d could not be set, aborting.\n", baud);
return false;
break;
}
// Finally, apply the configuration
if(tcsetattr(fd, TCSAFLUSH, &config) < 0)
{
fprintf(stderr, "\nERROR: could not set configuration of fd %d\n", fd);
return false;
}
// Done!
return true;
}
// ------------------------------------------------------------------------------
// Read Port with Lock
// ------------------------------------------------------------------------------
int
Serial_Port::
_read_port(uint8_t &cp)
{
// Lock
pthread_mutex_lock(&lock);
int result = read(fd, &cp, 1);
// Unlock
pthread_mutex_unlock(&lock);
return result;
}
// ------------------------------------------------------------------------------
// Write Port with Lock
// ------------------------------------------------------------------------------
int
Serial_Port::
_write_port(char *buf, unsigned len)
{
// Lock
pthread_mutex_lock(&lock);
// Write packet via serial link
const int bytesWritten = static_cast<int>(write(fd, buf, len));
// Wait until all data has been written
tcdrain(fd);
// Unlock
pthread_mutex_unlock(&lock);
return bytesWritten;
}