PX4 Firmware
PX4 Autopilot Software http://px4.io
IridiumSBD.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 #include <stdlib.h>
37 #include <stdbool.h>
38 
39 #include <lib/cdev/CDev.hpp>
40 #include <drivers/drv_hrt.h>
41 
42 #include <uORB/Publication.hpp>
46 
47 typedef enum {
48  SATCOM_OK = 0,
50  SATCOM_ERROR = -255,
52 
53 typedef enum {
57 
58 typedef enum {
63 
64 typedef enum {
72 
73 //typedef struct
74 //{
75 // uint8_t info;
76 // uint8_t result_code;
77 //} satcom_at_msg;
78 
79 typedef enum {
84 } satcom_state;
85 
86 extern "C" __EXPORT int iridiumsbd_main(int argc, char *argv[]);
87 
88 #define SATCOM_TX_BUF_LEN 340 // TX buffer size - maximum for a SBD MO message is 340, but billed per 50
89 #define SATCOM_MAX_MESSAGE_LENGTH 50 // Maximum length of the expected messages sent over this link
90 #define SATCOM_RX_MSG_BUF_LEN 270 // RX buffer size for MT messages
91 #define SATCOM_RX_COMMAND_BUF_LEN 50 // RX buffer size for other commands
92 #define SATCOM_SIGNAL_REFRESH_DELAY 20000000 // update signal quality every 20s
93 
94 /**
95  * The driver for the Rockblock 9602 and 9603 RockBlock module for satellite communication over the Iridium satellite system.
96  * The MavLink 1 protocol should be used to ensure that the status message is 50 bytes (RockBlock bills every 50 bytes per transmission).
97  *
98  * TODO:
99  * - Improve TX buffer handling:
100  * - Do not reset the full TX buffer but delete the oldest HIGH_LATENCY2 message if one is in the buffer or delete the oldest message in general
101  */
102 class IridiumSBD : public cdev::CDev
103 {
104 public:
105  /*
106  * Constructor
107  */
108  IridiumSBD();
109 
110  /*
111  * Start the driver
112  */
113  static int start(int argc, char *argv[]);
114 
115  /*
116  * Stop the driver
117  */
118  static int stop();
119 
120  /*
121  * Display driver status
122  */
123  static void status();
124 
125  /*
126  * Run a driver test based on the input
127  * - `s`: Send a test string
128  * - `read`: Start a sbd read session
129  * - else: Is assumed to be a valid AT command and written to the modem
130  */
131  static void test(int argc, char *argv[]);
132 
133  /*
134  * Passes everything to CDev
135  */
136  int ioctl(struct file *filp, int cmd, unsigned long arg);
137 
138 private:
139  /*
140  * Entry point of the task, has to be a static function
141  */
142  static void main_loop_helper(int argc, char *argv[]);
143 
144  /*
145  * Main driver loop
146  */
147  void main_loop(int argc, char *argv[]);
148 
149  /*
150  * Loop executed while in SATCOM_STATE_STANDBY
151  *
152  * Changes to SATCOM_STATE_TEST, SATCOM_STATE_SBDSESSION if required.
153  * Periodically changes to SATCOM_STATE_CSQ for a signal quality check.
154  */
155  void standby_loop(void);
156 
157  /*
158  * Loop executed while in SATCOM_STATE_CSQ
159  *
160  * Changes to SATCOM_STATE_STANDBY after finished signal quality check.
161  */
162  void csq_loop(void);
163 
164  /*
165  * Loop executed while in SATCOM_STATE_SBDSESSION
166  *
167  * Changes to SATCOM_STATE_STANDBY after finished sbd session.
168  */
169  void sbdsession_loop(void);
170 
171  /*
172  * Loop executed while in SATCOM_STATE_TEST
173  *
174  * Changes to SATCOM_STATE_STANDBY after finished test.
175  */
176  void test_loop(void);
177 
178  /*
179  * Get the network signal strength
180  */
181  void start_csq(void);
182 
183  /*
184  * Start a sbd session
185  */
186  void start_sbd_session(void);
187 
188  /*
189  * Check if the test command is valid. If that is the case
190  * change to SATCOM_STATE_TEST
191  */
192  void start_test(void);
193 
194  /*
195  * Use to send mavlink messages directly
196  */
197  ssize_t write(struct file *filp, const char *buffer, size_t buflen);
198 
199  /*
200  * Use to read received mavlink messages directly
201  */
202  ssize_t read(struct file *filp, char *buffer, size_t buflen);
203 
204  /*
205  * Write the tx buffer to the modem
206  */
207  void write_tx_buf();
208 
209  /*
210  * Read binary data from the modem
211  */
212  void read_rx_buf();
213 
214  /*
215  * Send a AT command to the modem
216  */
217  void write_at(const char *command);
218 
219  /*
220  * Read return from modem and store it in rx_command_buf
221  */
222  satcom_result_code read_at_command(int16_t timeout = 100);
223 
224  /*
225  * Read return from modem and store it in rx_msg_buf
226  */
227  satcom_result_code read_at_msg(int16_t timeout = 100);
228 
229  /*
230  * Read the return from the modem
231  */
232  satcom_result_code read_at(uint8_t *rx_buf, int *rx_len, int16_t timeout = 100);
233 
234  /*
235  * Schedule a test (set test_pending to true)
236  */
237  void schedule_test(void);
238 
239  /*
240  * Clear the MO message buffer
241  */
242  bool clear_mo_buffer();
243 
244  /*
245  * Open and configure the given UART port
246  */
247  satcom_uart_status open_uart(char *uart_name);
248 
249  /*
250  * Checks if the modem responds to the "AT" command
251  */
252  bool is_modem_ready(void);
253 
254  /*
255  * Get the poll state
256  */
257  pollevent_t poll_state(struct file *filp);
258 
259  void publish_iridium_status(void);
260 
262 
263  /**
264  * Notification of the first open of CDev.
265  *
266  * This function is called when the device open count transitions from zero
267  * to one. The driver lock is held for the duration of the call.
268  *
269  * Notes that CDev is used and blocks stopping the driver.
270  *
271  * @param filep Pointer to the NuttX file structure.
272  * @return OK if the open should proceed, -errno otherwise.
273  */
274  virtual int open_first(struct file *filep) override;
275 
276  /**
277  * Notification of the last close of CDev.
278  *
279  * This function is called when the device open count transitions from
280  * one to zero. The driver lock is held for the duration of the call.
281  *
282  * Notes that CDev is not used anymore and allows stopping the driver.
283  *
284  * @param filep Pointer to the NuttX file structure.
285  * @return OK if the open should return OK, -errno otherwise.
286  */
287  virtual int close_last(struct file *filep) override;
288 
290  static int task_handle;
291  bool _task_should_exit = false;
292  bool _start_completed = false;
293  int uart_fd = -1;
294 
298 
300  uint8_t _signal_quality = 0;
301  uint16_t _failed_sbd_sessions = 0;
303  uint16_t _num_tx_buf_reset = 0;
304 
306  uint16_t _packet_length = 0;
307 
310 
311  bool _test_pending = false;
312  char _test_command[32];
314 
317 
321 
322  uint8_t _tx_buf[SATCOM_TX_BUF_LEN] = {};
324 
325  bool _tx_buf_write_pending = false;
326  bool _ring_pending = false;
327  bool _rx_session_pending = false;
328  bool _rx_read_pending = false;
329  bool _tx_session_pending = false;
330 
331  bool _cdev_used = false;
332 
337 
340 
341  pthread_mutex_t _tx_buf_mutex = pthread_mutex_t();
342  pthread_mutex_t _rx_buf_mutex = pthread_mutex_t();
343 
344  bool _verbose = false;
345 
348 };
void test_loop(void)
Definition: IridiumSBD.cpp:583
#define SATCOM_RX_MSG_BUF_LEN
Definition: IridiumSBD.h:90
int _rx_msg_end_idx
Definition: IridiumSBD.h:319
virtual int open_first(struct file *filep) override
Notification of the first open of CDev.
pollevent_t poll_state(struct file *filp)
bool _ring_pending
Definition: IridiumSBD.h:326
#define SATCOM_RX_COMMAND_BUF_LEN
Definition: IridiumSBD.h:91
hrt_abstime _test_timer
Definition: IridiumSBD.h:313
void write_tx_buf()
Definition: IridiumSBD.cpp:776
satcom_state _state
Definition: IridiumSBD.h:338
__EXPORT int iridiumsbd_main(int argc, char *argv[])
void sbdsession_loop(void)
Definition: IridiumSBD.cpp:471
static void test(int argc, char *argv[])
Definition: IridiumSBD.cpp:164
bool _rx_session_pending
Definition: IridiumSBD.h:327
void schedule_test(void)
Definition: IridiumSBD.cpp:970
void read_rx_buf()
Definition: IridiumSBD.cpp:837
hrt_abstime _session_start_time
Definition: IridiumSBD.h:336
bool _tx_buf_write_pending
Definition: IridiumSBD.h:325
satcom_read_status
Definition: IridiumSBD.h:58
hrt_abstime _last_write_time
Definition: IridiumSBD.h:333
Definition: I2C.hpp:51
void csq_loop(void)
Definition: IridiumSBD.cpp:441
void standby_loop(void)
Definition: IridiumSBD.cpp:375
hrt_abstime _last_heartbeat
Definition: IridiumSBD.h:335
bool clear_mo_buffer()
Definition: IridiumSBD.cpp:975
int _rx_msg_read_idx
Definition: IridiumSBD.h:320
satcom_state
Definition: IridiumSBD.h:79
void publish_iridium_status(void)
virtual int close_last(struct file *filep) override
Notification of the last close of CDev.
satcom_result_code read_at_command(int16_t timeout=100)
Definition: IridiumSBD.cpp:895
uint16_t _packet_length
Definition: IridiumSBD.h:306
bool _tx_session_pending
Definition: IridiumSBD.h:329
uORB::Publication< iridiumsbd_status_s > _iridiumsbd_status_pub
Definition: IridiumSBD.h:308
High-resolution timer with callouts and timekeeping.
bool _writing_mavlink_packet
Definition: IridiumSBD.h:305
uint8_t _signal_quality
Definition: IridiumSBD.h:300
subsystem_info_s _info
Definition: IridiumSBD.h:347
uint8_t _tx_buf[SATCOM_TX_BUF_LEN]
Definition: IridiumSBD.h:322
static int task_handle
Definition: IridiumSBD.h:290
static int stop()
Definition: IridiumSBD.cpp:107
bool _cdev_used
Definition: IridiumSBD.h:331
bool _start_completed
Definition: IridiumSBD.h:292
int _tx_buf_write_idx
Definition: IridiumSBD.h:323
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
void main_loop(int argc, char *argv[])
Definition: IridiumSBD.cpp:230
uint16_t _failed_sbd_sessions
Definition: IridiumSBD.h:301
ssize_t write(struct file *filp, const char *buffer, size_t buflen)
Definition: IridiumSBD.cpp:691
Abstract class for any character device.
Definition: CDev.hpp:58
The driver for the Rockblock 9602 and 9603 RockBlock module for satellite communication over the Irid...
Definition: IridiumSBD.h:102
hrt_abstime _last_signal_check
Definition: IridiumSBD.h:299
bool _test_pending
Definition: IridiumSBD.h:311
int _rx_command_len
Definition: IridiumSBD.h:316
uint16_t _num_tx_buf_reset
Definition: IridiumSBD.h:303
satcom_uart_status
Definition: IridiumSBD.h:53
ssize_t read(struct file *filp, char *buffer, size_t buflen)
Definition: IridiumSBD.cpp:751
satcom_uart_status open_uart(char *uart_name)
Definition: IridiumSBD.cpp:987
satcom_result_code read_at(uint8_t *rx_buf, int *rx_len, int16_t timeout=100)
Definition: IridiumSBD.cpp:905
int32_t _param_stacking_time_ms
Definition: IridiumSBD.h:297
bool _verbose
Definition: IridiumSBD.h:344
bool _rx_read_pending
Definition: IridiumSBD.h:328
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
void start_test(void)
Definition: IridiumSBD.cpp:650
bool is_modem_ready(void)
char _test_command[32]
Definition: IridiumSBD.h:312
uint16_t _successful_sbd_sessions
Definition: IridiumSBD.h:302
pthread_mutex_t _rx_buf_mutex
Definition: IridiumSBD.h:342
satcom_result_code read_at_msg(int16_t timeout=100)
Definition: IridiumSBD.cpp:900
struct @83::@85::@87 file
#define SATCOM_TX_BUF_LEN
Definition: IridiumSBD.h:88
static IridiumSBD * instance
Definition: IridiumSBD.h:289
static int start(int argc, char *argv[])
Definition: IridiumSBD.cpp:68
int32_t _param_read_interval_s
Definition: IridiumSBD.h:295
void start_sbd_session(void)
Definition: IridiumSBD.cpp:621
void start_csq(void)
Definition: IridiumSBD.cpp:600
bool _task_should_exit
Definition: IridiumSBD.h:291
void write_at(const char *command)
Definition: IridiumSBD.cpp:887
static void status()
Definition: IridiumSBD.cpp:145
iridiumsbd_status_s _status
Definition: IridiumSBD.h:346
uint8_t _rx_msg_buf[SATCOM_RX_MSG_BUF_LEN]
Definition: IridiumSBD.h:318
static void main_loop_helper(int argc, char *argv[])
Definition: IridiumSBD.cpp:216
uORB::PublicationQueued< subsystem_info_s > _subsystem_pub
Definition: IridiumSBD.h:309
satcom_state _new_state
Definition: IridiumSBD.h:339
uint8_t _rx_command_buf[SATCOM_RX_COMMAND_BUF_LEN]
Definition: IridiumSBD.h:315
int32_t _param_session_timeout_s
Definition: IridiumSBD.h:296
void publish_subsystem_status()
satcom_status
Definition: IridiumSBD.h:47
pthread_mutex_t _tx_buf_mutex
Definition: IridiumSBD.h:341
hrt_abstime _last_read_time
Definition: IridiumSBD.h:334
int ioctl(struct file *filp, int cmd, unsigned long arg)
Definition: IridiumSBD.cpp:187
satcom_result_code
Definition: IridiumSBD.h:64