PX4 Firmware
PX4 Autopilot Software http://px4.io
linux_sbus.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2017 Mark Charl. All rights reserved.
4  * Copyright (C) 2017 Fan.zhang. All rights reserved.
5  * Copyright (C) 2017 PX4 Development Team. All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * 1. Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * 2. Redistributions in binary form must reproduce the above copyright
14  * notice, this list of conditions and the following disclaimer in
15  * the documentation and/or other materials provided with the
16  * distribution.
17  * 3. Neither the name PX4 nor the names of its contributors may be
18  * used to endorse or promote products derived from this software
19  * without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
28  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
29  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  ****************************************************************************/
35 
36 #pragma once
37 
38 #include <sys/types.h>
39 #include <sys/stat.h>
40 #include <sys/ipc.h>
41 #include <fcntl.h>
42 #include <stdio.h>
43 #include <stdint.h>
44 #include <unistd.h>
45 #include <fcntl.h>
46 #include <sys/ioctl.h>
47 /*For terminal I/O interfaces, termbits.h from asm-generic versions of functions guarantees non-standard communication (100Khz, Non-blocking), not guaranteed by termios.h*/
48 #include <asm-generic/termbits.h>
49 #include <errno.h>
50 #include <px4_platform_common/px4_config.h>
51 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
52 #include <px4_platform_common/defines.h>
53 #include <drivers/drv_hrt.h>
54 #include <uORB/uORB.h>
55 #include <uORB/topics/input_rc.h>
56 /* The interval between each frame is 4700us, do not change it. */
57 #define RCINPUT_MEASURE_INTERVAL_US 4700
58 /* define range mapping here, -+100% -> 1000..2000 */
59 #define SBUS_RANGE_MIN 200.0f
60 #define SBUS_RANGE_MAX 1800.0f
61 #define SBUS_TARGET_MIN 1000.0f
62 #define SBUS_TARGET_MAX 2000.0f
63 /* pre-calculate the floating point stuff as far as possible at compile time */
64 #define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
65 #define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
66 
67 namespace linux_sbus
68 {
69 class RcInput : public px4::ScheduledWorkItem
70 {
71 public:
72  RcInput() :
73  ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
74  _shouldExit(false),
75  _isRunning(false),
76  _rcinput_pub(nullptr),
77  _data { }, _sbusData { 0x0f, 0x01, 0x04, 0x20, 0x00,
78  0xff, 0x07, 0x40, 0x00, 0x02,
79  0x10, 0x80, 0x2c, 0x64, 0x21,
80  0x0b, 0x59, 0x08, 0x40, 0x00,
81  0x02, 0x10, 0x80, 0x00, 0x00 }
82  { }
84  {
85  ScheduleClear();
86  _isRunning = false;
87  close(_device_fd);
88  }
89  /** @return 0 on success, -errno on failure */
90  int start(char *device, int channels);
91  void stop();
92 
93  bool isRunning()
94  {
95  return _isRunning;
96  }
97 
98 private:
99  void Run() override;
100  void _measure();
105  uint8_t _sbusData[25];
107  int _device_fd; /** serial port device to read SBUS; */
108  int _channels_data[16]; /** 16 channels support; */
109  uint8_t _buffer[25];
110  char _device[30];
111  bool _failsafe;
112  bool _rc_loss;
113  int init();
114 };
115 
116 static void usage(const char *reason);
117 static RcInput *rc_input = nullptr;
118 }
119 extern "C" __EXPORT int linux_sbus_main(int argc, char **argv);
static void usage(const char *reason)
Print the correct usage.
Definition: Commander.cpp:4238
API for the uORB lightweight object broker.
static RcInput * rc_input
Definition: linux_sbus.h:117
struct input_rc_s _data
Definition: linux_sbus.h:104
int start(char *device, int channels)
Definition: linux_sbus.cpp:108
Definition: I2C.hpp:51
void Run() override
Definition: linux_sbus.cpp:139
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
High-resolution timer with callouts and timekeeping.
int _channels_data[16]
serial port device to read SBUS;
Definition: linux_sbus.h:108
orb_advert_t _rcinput_pub
Definition: linux_sbus.h:103
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
__EXPORT int linux_sbus_main(int argc, char **argv)
Definition: linux_sbus.cpp:249
uint8_t _sbusData[25]
Definition: linux_sbus.h:105
Definition: bst.cpp:62
uint8_t _buffer[25]
16 channels support;
Definition: linux_sbus.h:109