RCOutput_Tap_Linux.cpp 1.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263
  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. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  19. #include "RCOutput_Tap.h"
  20. #include <asm/termbits.h>
  21. #include <string.h>
  22. #include <sys/ioctl.h>
  23. #include <sys/stat.h>
  24. #include <sys/types.h>
  25. namespace ap {
  26. bool RCOutput_Tap::_uart_set_speed(int speed)
  27. {
  28. struct termios2 tc;
  29. if (_uart_fd < 0) {
  30. return false;
  31. }
  32. memset(&tc, 0, sizeof(tc));
  33. if (ioctl(_uart_fd, TCGETS2, &tc) == -1) {
  34. return false;
  35. }
  36. /* speed is configured by c_[io]speed */
  37. tc.c_cflag &= ~CBAUD;
  38. tc.c_cflag |= BOTHER;
  39. tc.c_ispeed = speed;
  40. tc.c_ospeed = speed;
  41. if (ioctl(_uart_fd, TCSETS2, &tc) == -1) {
  42. return false;
  43. }
  44. if (ioctl(_uart_fd, TCFLSH, TCIOFLUSH) == -1) {
  45. return false;
  46. }
  47. return true;
  48. }
  49. }
  50. #endif