APM:Libraries
libraries
AP_HAL
utility
RCOutput_Tap_Nuttx.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2017 Intel Corporation. All rights reserved.
3
*
4
* This file is free software: you can redistribute it and/or modify it
5
* under the terms of the GNU General Public License as published by the
6
* Free Software Foundation, either version 3 of the License, or
7
* (at your option) any later version.
8
*
9
* This file is distributed in the hope that it will be useful, but
10
* WITHOUT ANY WARRANTY; without even the implied warranty of
11
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12
* See the GNU General Public License for more details.
13
*
14
* You should have received a copy of the GNU General Public License along
15
* with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
#include <
AP_HAL/AP_HAL.h
>
18
19
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_AEROFC_V1
20
21
#include "
RCOutput_Tap.h
"
22
23
#include <termios.h>
24
#include <string.h>
25
26
namespace
ap
{
27
28
bool
RCOutput_Tap::_uart_set_speed
(
int
speed)
29
{
30
if
(
_uart_fd
< 0) {
31
return
false
;
32
}
33
34
struct
termios uart_config;
35
memset(&uart_config, 0,
sizeof
(uart_config));
36
tcgetattr(
_uart_fd
, &uart_config);
37
38
// set baud rate
39
if
(cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
40
return
false
;
41
}
42
43
if
(tcsetattr(
_uart_fd
, TCSANOW, &uart_config) < 0) {
44
return
false
;
45
}
46
47
return
true
;
48
}
49
50
}
51
52
#endif
ap::RCOutput_Tap::_uart_set_speed
bool _uart_set_speed(int speed)
Definition:
RCOutput_Tap_Linux.cpp:31
AP_HAL.h
ap
Definition:
RCOutput_Tap.h:54
ap::RCOutput_Tap::_uart_fd
int _uart_fd
Definition:
RCOutput_Tap.h:100
RCOutput_Tap.h
Generated on Sun Jun 17 2018 14:18:48 for APM:Libraries by
1.8.13