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 113 static int start(
int argc,
char *argv[]);
131 static void test(
int argc,
char *argv[]);
136 int ioctl(
struct file *filp,
int cmd,
unsigned long arg);
197 ssize_t
write(
struct file *filp,
const char *buffer,
size_t buflen);
202 ssize_t
read(
struct file *filp,
char *buffer,
size_t buflen);
#define SATCOM_RX_MSG_BUF_LEN
virtual int open_first(struct file *filep) override
Notification of the first open of CDev.
pollevent_t poll_state(struct file *filp)
#define SATCOM_RX_COMMAND_BUF_LEN
__EXPORT int iridiumsbd_main(int argc, char *argv[])
void sbdsession_loop(void)
static void test(int argc, char *argv[])
hrt_abstime _session_start_time
bool _tx_buf_write_pending
hrt_abstime _last_write_time
hrt_abstime _last_heartbeat
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)
uORB::Publication< iridiumsbd_status_s > _iridiumsbd_status_pub
High-resolution timer with callouts and timekeeping.
bool _writing_mavlink_packet
uint8_t _tx_buf[SATCOM_TX_BUF_LEN]
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
void main_loop(int argc, char *argv[])
uint16_t _failed_sbd_sessions
ssize_t write(struct file *filp, const char *buffer, size_t buflen)
Abstract class for any character device.
The driver for the Rockblock 9602 and 9603 RockBlock module for satellite communication over the Irid...
hrt_abstime _last_signal_check
uint16_t _num_tx_buf_reset
ssize_t read(struct file *filp, char *buffer, size_t buflen)
satcom_uart_status open_uart(char *uart_name)
satcom_result_code read_at(uint8_t *rx_buf, int *rx_len, int16_t timeout=100)
int32_t _param_stacking_time_ms
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
bool is_modem_ready(void)
uint16_t _successful_sbd_sessions
pthread_mutex_t _rx_buf_mutex
satcom_result_code read_at_msg(int16_t timeout=100)
struct @83::@85::@87 file
#define SATCOM_TX_BUF_LEN
static IridiumSBD * instance
static int start(int argc, char *argv[])
int32_t _param_read_interval_s
void start_sbd_session(void)
void write_at(const char *command)
iridiumsbd_status_s _status
uint8_t _rx_msg_buf[SATCOM_RX_MSG_BUF_LEN]
static void main_loop_helper(int argc, char *argv[])
uORB::PublicationQueued< subsystem_info_s > _subsystem_pub
uint8_t _rx_command_buf[SATCOM_RX_COMMAND_BUF_LEN]
int32_t _param_session_timeout_s
void publish_subsystem_status()
pthread_mutex_t _tx_buf_mutex
hrt_abstime _last_read_time
int ioctl(struct file *filp, int cmd, unsigned long arg)