PX4 Firmware
PX4 Autopilot Software http://px4.io
IridiumSBD Class Reference

The driver for the Rockblock 9602 and 9603 RockBlock module for satellite communication over the Iridium satellite system. More...

#include <IridiumSBD.h>

Inheritance diagram for IridiumSBD:
Collaboration diagram for IridiumSBD:

Public Member Functions

 IridiumSBD ()
 
int ioctl (struct file *filp, int cmd, unsigned long arg)
 
- Public Member Functions inherited from cdev::CDev
 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (CDev &&)=delete
 
virtual ~CDev ()
 
virtual int init ()
 
virtual int open (file_t *filep)
 Handle an open of the device. More...
 
virtual int close (file_t *filep)
 Handle a close of the device. More...
 
virtual ssize_t read (file_t *filep, char *buffer, size_t buflen)
 Perform a read from the device. More...
 
virtual ssize_t write (file_t *filep, const char *buffer, size_t buflen)
 Perform a write to the device. More...
 
virtual off_t seek (file_t *filep, off_t offset, int whence)
 Perform a logical seek operation on the device. More...
 
virtual int ioctl (file_t *filep, int cmd, unsigned long arg)
 Perform an ioctl operation on the device. More...
 
virtual int poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 Perform a poll setup/teardown operation. More...
 
const char * get_devname () const
 Get the device name. More...
 

Static Public Member Functions

static int start (int argc, char *argv[])
 
static int stop ()
 
static void status ()
 
static void test (int argc, char *argv[])
 

Private Member Functions

void main_loop (int argc, char *argv[])
 
void standby_loop (void)
 
void csq_loop (void)
 
void sbdsession_loop (void)
 
void test_loop (void)
 
void start_csq (void)
 
void start_sbd_session (void)
 
void start_test (void)
 
ssize_t write (struct file *filp, const char *buffer, size_t buflen)
 
ssize_t read (struct file *filp, char *buffer, size_t buflen)
 
void write_tx_buf ()
 
void read_rx_buf ()
 
void write_at (const char *command)
 
satcom_result_code read_at_command (int16_t timeout=100)
 
satcom_result_code read_at_msg (int16_t timeout=100)
 
satcom_result_code read_at (uint8_t *rx_buf, int *rx_len, int16_t timeout=100)
 
void schedule_test (void)
 
bool clear_mo_buffer ()
 
satcom_uart_status open_uart (char *uart_name)
 
bool is_modem_ready (void)
 
pollevent_t poll_state (struct file *filp)
 
void publish_iridium_status (void)
 
void publish_subsystem_status ()
 
virtual int open_first (struct file *filep) override
 Notification of the first open of CDev. More...
 
virtual int close_last (struct file *filep) override
 Notification of the last close of CDev. More...
 

Static Private Member Functions

static void main_loop_helper (int argc, char *argv[])
 

Private Attributes

bool _task_should_exit = false
 
bool _start_completed = false
 
int uart_fd = -1
 
int32_t _param_read_interval_s = -1
 
int32_t _param_session_timeout_s = -1
 
int32_t _param_stacking_time_ms = -1
 
hrt_abstime _last_signal_check = 0
 
uint8_t _signal_quality = 0
 
uint16_t _failed_sbd_sessions = 0
 
uint16_t _successful_sbd_sessions = 0
 
uint16_t _num_tx_buf_reset = 0
 
bool _writing_mavlink_packet = false
 
uint16_t _packet_length = 0
 
uORB::Publication< iridiumsbd_status_s_iridiumsbd_status_pub {ORB_ID(iridiumsbd_status)}
 
uORB::PublicationQueued< subsystem_info_s_subsystem_pub {ORB_ID(subsystem_info)}
 
bool _test_pending = false
 
char _test_command [32]
 
hrt_abstime _test_timer = 0
 
uint8_t _rx_command_buf [SATCOM_RX_COMMAND_BUF_LEN] = {}
 
int _rx_command_len = 0
 
uint8_t _rx_msg_buf [SATCOM_RX_MSG_BUF_LEN] = {}
 
int _rx_msg_end_idx = 0
 
int _rx_msg_read_idx = 0
 
uint8_t _tx_buf [SATCOM_TX_BUF_LEN] = {}
 
int _tx_buf_write_idx = 0
 
bool _tx_buf_write_pending = false
 
bool _ring_pending = false
 
bool _rx_session_pending = false
 
bool _rx_read_pending = false
 
bool _tx_session_pending = false
 
bool _cdev_used = false
 
hrt_abstime _last_write_time = 0
 
hrt_abstime _last_read_time = 0
 
hrt_abstime _last_heartbeat = 0
 
hrt_abstime _session_start_time = 0
 
satcom_state _state = SATCOM_STATE_STANDBY
 
satcom_state _new_state = SATCOM_STATE_STANDBY
 
pthread_mutex_t _tx_buf_mutex = pthread_mutex_t()
 
pthread_mutex_t _rx_buf_mutex = pthread_mutex_t()
 
bool _verbose = false
 
iridiumsbd_status_s _status = {}
 
subsystem_info_s _info = {}
 

Static Private Attributes

static IridiumSBDinstance
 
static int task_handle
 

Additional Inherited Members

- Protected Member Functions inherited from cdev::CDev
virtual pollevent_t poll_state (file_t *filep)
 Check the current state of the device for poll events from the perspective of the file. More...
 
virtual void poll_notify (pollevent_t events)
 Report new poll events. More...
 
virtual void poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events)
 Internal implementation of poll_notify. More...
 
virtual int open_first (file_t *filep)
 Notification of the first open. More...
 
virtual int close_last (file_t *filep)
 Notification of the last close. More...
 
virtual int register_class_devname (const char *class_devname)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
virtual int unregister_class_devname (const char *class_devname, unsigned class_instance)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
void lock ()
 Take the driver lock. More...
 
void unlock ()
 Release the driver lock. More...
 
int unregister_driver_and_memory ()
 First, unregisters the driver. More...
 
- Protected Attributes inherited from cdev::CDev
px4_sem_t _lock
 lock to protect access to all class members (also for derived classes) More...
 
- Static Protected Attributes inherited from cdev::CDev
static const px4_file_operations_t fops = {}
 Pointer to the default cdev file operations table; useful for registering clone devices etc. More...
 

Detailed Description

The driver for the Rockblock 9602 and 9603 RockBlock module for satellite communication over the Iridium satellite system.

The MavLink 1 protocol should be used to ensure that the status message is 50 bytes (RockBlock bills every 50 bytes per transmission).

TODO:

  • Improve TX buffer handling:
    • 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

Definition at line 102 of file IridiumSBD.h.

Constructor & Destructor Documentation

◆ IridiumSBD()

IridiumSBD::IridiumSBD ( )

Definition at line 59 of file IridiumSBD.cpp.

Referenced by start().

Here is the caller graph for this function:

Member Function Documentation

◆ clear_mo_buffer()

bool IridiumSBD::clear_mo_buffer ( )
private

Definition at line 975 of file IridiumSBD.cpp.

References _rx_command_buf, read_at_command(), SATCOM_RESULT_OK, VERBOSE_INFO, and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ close_last()

int IridiumSBD::close_last ( struct file filep)
overrideprivatevirtual

Notification of the last close of CDev.

This function is called when the device open count transitions from one to zero. The driver lock is held for the duration of the call.

Notes that CDev is not used anymore and allows stopping the driver.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the open should return OK, -errno otherwise.

Definition at line 1142 of file IridiumSBD.cpp.

References _cdev_used.

◆ csq_loop()

void IridiumSBD::csq_loop ( void  )
private

Definition at line 441 of file IridiumSBD.cpp.

References _new_state, _rx_command_buf, _signal_quality, read_at_command(), SATCOM_RESULT_NA, SATCOM_RESULT_OK, SATCOM_STATE_STANDBY, and VERBOSE_INFO.

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ioctl()

int IridiumSBD::ioctl ( struct file filp,
int  cmd,
unsigned long  arg 
)

◆ is_modem_ready()

bool IridiumSBD::is_modem_ready ( void  )
private

Definition at line 1009 of file IridiumSBD.cpp.

References read_at_command(), SATCOM_RESULT_OK, and write_at().

Referenced by read_rx_buf(), start_csq(), start_sbd_session(), start_test(), and write_tx_buf().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ main_loop()

void IridiumSBD::main_loop ( int  argc,
char *  argv[] 
)
private

Definition at line 230 of file IridiumSBD.cpp.

References _new_state, _param_read_interval_s, _param_session_timeout_s, _param_stacking_time_ms, _rx_buf_mutex, _start_completed, _state, _task_should_exit, _tx_buf_mutex, _verbose, counter, csq_loop(), ToneAlarmInterface::init(), open_uart(), param_find(), param_get(), publish_iridium_status(), publish_subsystem_status(), read_at_command(), SATCOM_RESULT_OK, SATCOM_STATE_CSQ, SATCOM_STATE_SBDSESSION, SATCOM_STATE_STANDBY, satcom_state_string, SATCOM_STATE_TEST, SATCOM_UART_OK, sbdsession_loop(), standby_loop(), test_loop(), VERBOSE_INFO, and write_at().

Referenced by main_loop_helper().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ main_loop_helper()

void IridiumSBD::main_loop_helper ( int  argc,
char *  argv[] 
)
staticprivate

Definition at line 216 of file IridiumSBD.cpp.

References cdev::CDev::close(), instance, main_loop(), task_handle, and uart_fd.

Referenced by start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ open_first()

int IridiumSBD::open_first ( struct file filep)
overrideprivatevirtual

Notification of the first open of CDev.

This function is called when the device open count transitions from zero to one. The driver lock is held for the duration of the call.

Notes that CDev is used and blocks stopping the driver.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the open should proceed, -errno otherwise.

Definition at line 1136 of file IridiumSBD.cpp.

References _cdev_used.

◆ open_uart()

satcom_uart_status IridiumSBD::open_uart ( char *  uart_name)
private

Definition at line 987 of file IridiumSBD.cpp.

References cdev::CDev::open(), SATCOM_UART_OK, SATCOM_UART_OPEN_FAIL, uart_fd, and VERBOSE_INFO.

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ poll_state()

pollevent_t IridiumSBD::poll_state ( struct file filp)
private

◆ publish_iridium_status()

◆ publish_subsystem_status()

void IridiumSBD::publish_subsystem_status ( )
private

Definition at line 1118 of file IridiumSBD.cpp.

References _info, _status, _subsystem_pub, subsystem_info_s::enabled, hrt_absolute_time(), iridiumsbd_status_s::last_heartbeat, subsystem_info_s::ok, subsystem_info_s::present, uORB::PublicationQueued< T >::publish(), subsystem_info_s::subsystem_type, and subsystem_info_s::timestamp.

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read()

ssize_t IridiumSBD::read ( struct file filp,
char *  buffer,
size_t  buflen 
)
private

Definition at line 751 of file IridiumSBD.cpp.

References _rx_buf_mutex, _rx_msg_buf, _rx_msg_end_idx, _rx_msg_read_idx, and VERBOSE_INFO.

Referenced by read_at().

Here is the caller graph for this function:

◆ read_at()

satcom_result_code IridiumSBD::read_at ( uint8_t *  rx_buf,
int *  rx_len,
int16_t  timeout = 100 
)
private

Definition at line 905 of file IridiumSBD.cpp.

References _ring_pending, _rx_session_pending, cdev::CDev::poll(), read(), SATCOM_RESULT_ERROR, SATCOM_RESULT_HWFAIL, SATCOM_RESULT_NA, SATCOM_RESULT_OK, SATCOM_RESULT_READY, SATCOM_RESULT_SBDRING, uart_fd, and VERBOSE_INFO.

Referenced by read_at_command(), and read_at_msg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_at_command()

satcom_result_code IridiumSBD::read_at_command ( int16_t  timeout = 100)
private

Definition at line 895 of file IridiumSBD.cpp.

References _rx_command_buf, _rx_command_len, and read_at().

Referenced by clear_mo_buffer(), csq_loop(), is_modem_ready(), main_loop(), sbdsession_loop(), standby_loop(), start_test(), test_loop(), and write_tx_buf().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_at_msg()

satcom_result_code IridiumSBD::read_at_msg ( int16_t  timeout = 100)
private

Definition at line 900 of file IridiumSBD.cpp.

References _rx_msg_buf, _rx_msg_end_idx, and read_at().

Referenced by read_rx_buf().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_rx_buf()

void IridiumSBD::read_rx_buf ( void  )
private

Definition at line 837 of file IridiumSBD.cpp.

References _rx_buf_mutex, _rx_msg_buf, _rx_msg_end_idx, _rx_msg_read_idx, _rx_read_pending, is_modem_ready(), read_at_msg(), SATCOM_RESULT_OK, VERBOSE_INFO, and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ sbdsession_loop()

void IridiumSBD::sbdsession_loop ( void  )
private

Definition at line 471 of file IridiumSBD.cpp.

References _failed_sbd_sessions, _last_heartbeat, _last_read_time, _new_state, _param_session_timeout_s, _ring_pending, _rx_command_buf, _rx_read_pending, _rx_session_pending, _session_start_time, _signal_quality, _successful_sbd_sessions, _tx_buf_mutex, _tx_buf_write_idx, _tx_session_pending, hrt_absolute_time(), read_at_command(), SATCOM_RESULT_NA, SATCOM_RESULT_OK, SATCOM_STATE_STANDBY, and VERBOSE_INFO.

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ schedule_test()

void IridiumSBD::schedule_test ( void  )
private

Definition at line 970 of file IridiumSBD.cpp.

References _test_pending.

Referenced by test().

Here is the caller graph for this function:

◆ standby_loop()

void IridiumSBD::standby_loop ( void  )
private

Definition at line 375 of file IridiumSBD.cpp.

References _last_read_time, _last_signal_check, _last_write_time, _new_state, _param_read_interval_s, _param_stacking_time_ms, _rx_msg_end_idx, _rx_msg_read_idx, _rx_read_pending, _rx_session_pending, _signal_quality, _test_command, _test_pending, _test_timer, _tx_buf_write_pending, _tx_session_pending, clear_mo_buffer(), hrt_absolute_time(), read_at_command(), read_rx_buf(), SATCOM_SIGNAL_REFRESH_DELAY, SATCOM_STATE_STANDBY, start_csq(), start_sbd_session(), start_test(), write(), and write_tx_buf().

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

int IridiumSBD::start ( int  argc,
char *  argv[] 
)
static

Definition at line 68 of file IridiumSBD.cpp.

References _start_completed, _task_should_exit, counter, IridiumSBD(), main_loop_helper(), and task_handle.

Referenced by iridiumsbd_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_csq()

void IridiumSBD::start_csq ( void  )
private

Definition at line 600 of file IridiumSBD.cpp.

References _last_signal_check, _new_state, _state, hrt_absolute_time(), is_modem_ready(), SATCOM_STATE_CSQ, SATCOM_STATE_STANDBY, VERBOSE_INFO, and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_sbd_session()

void IridiumSBD::start_sbd_session ( void  )
private

Definition at line 621 of file IridiumSBD.cpp.

References _new_state, _ring_pending, _session_start_time, _state, _tx_buf_mutex, hrt_absolute_time(), is_modem_ready(), SATCOM_STATE_SBDSESSION, SATCOM_STATE_STANDBY, VERBOSE_INFO, and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_test()

void IridiumSBD::start_test ( void  )
private

Definition at line 650 of file IridiumSBD.cpp.

References _new_state, _rx_command_buf, _rx_command_len, _state, _test_command, is_modem_ready(), read_at_command(), SATCOM_RESULT_NA, SATCOM_STATE_STANDBY, SATCOM_STATE_TEST, and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ status()

void IridiumSBD::status ( )
static

Definition at line 145 of file IridiumSBD.cpp.

References _last_heartbeat, _last_signal_check, _rx_read_pending, _rx_session_pending, _signal_quality, _state, _tx_buf_write_idx, _tx_session_pending, hrt_absolute_time(), instance, and satcom_state_string.

Referenced by iridiumsbd_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop()

int IridiumSBD::stop ( )
static

Definition at line 107 of file IridiumSBD.cpp.

References _cdev_used, _task_should_exit, cdev::CDev::close(), instance, OK, task_handle, and uart_fd.

Referenced by iridiumsbd_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ test()

void IridiumSBD::test ( int  argc,
char *  argv[] 
)
static

Definition at line 164 of file IridiumSBD.cpp.

References _state, _test_command, _test_pending, instance, SATCOM_STATE_STANDBY, and schedule_test().

Referenced by iridiumsbd_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ test_loop()

void IridiumSBD::test_loop ( void  )
private

Definition at line 583 of file IridiumSBD.cpp.

References _new_state, _rx_command_buf, _rx_command_len, _test_timer, hrt_absolute_time(), read_at_command(), SATCOM_RESULT_NA, and SATCOM_STATE_STANDBY.

Referenced by main_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write()

ssize_t IridiumSBD::write ( struct file filp,
const char *  buffer,
size_t  buflen 
)
private

Definition at line 691 of file IridiumSBD.cpp.

References _last_write_time, _num_tx_buf_reset, _packet_length, _tx_buf, _tx_buf_mutex, _tx_buf_write_idx, _tx_buf_write_pending, _writing_mavlink_packet, hrt_absolute_time(), SATCOM_TX_BUF_LEN, and VERBOSE_INFO.

Referenced by standby_loop(), write_at(), and write_tx_buf().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_at()

void IridiumSBD::write_at ( const char *  command)
private

Definition at line 887 of file IridiumSBD.cpp.

References uart_fd, VERBOSE_INFO, and write().

Referenced by clear_mo_buffer(), is_modem_ready(), main_loop(), read_rx_buf(), start_csq(), start_sbd_session(), start_test(), and write_tx_buf().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_tx_buf()

void IridiumSBD::write_tx_buf ( )
private

Definition at line 776 of file IridiumSBD.cpp.

References _rx_command_buf, _tx_buf, _tx_buf_mutex, _tx_buf_write_idx, _tx_buf_write_pending, _tx_session_pending, command, is_modem_ready(), read_at_command(), SATCOM_RESULT_OK, SATCOM_RESULT_READY, uart_fd, VERBOSE_INFO, write(), and write_at().

Referenced by standby_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _cdev_used

bool IridiumSBD::_cdev_used = false
private

Definition at line 331 of file IridiumSBD.h.

Referenced by close_last(), open_first(), and stop().

◆ _failed_sbd_sessions

uint16_t IridiumSBD::_failed_sbd_sessions = 0
private

Definition at line 301 of file IridiumSBD.h.

Referenced by publish_iridium_status(), and sbdsession_loop().

◆ _info

subsystem_info_s IridiumSBD::_info = {}
private

Definition at line 347 of file IridiumSBD.h.

Referenced by publish_subsystem_status().

◆ _iridiumsbd_status_pub

uORB::Publication<iridiumsbd_status_s> IridiumSBD::_iridiumsbd_status_pub {ORB_ID(iridiumsbd_status)}
private

Definition at line 308 of file IridiumSBD.h.

Referenced by publish_iridium_status().

◆ _last_heartbeat

hrt_abstime IridiumSBD::_last_heartbeat = 0
private

Definition at line 335 of file IridiumSBD.h.

Referenced by publish_iridium_status(), sbdsession_loop(), and status().

◆ _last_read_time

hrt_abstime IridiumSBD::_last_read_time = 0
private

Definition at line 334 of file IridiumSBD.h.

Referenced by sbdsession_loop(), and standby_loop().

◆ _last_signal_check

hrt_abstime IridiumSBD::_last_signal_check = 0
private

Definition at line 299 of file IridiumSBD.h.

Referenced by standby_loop(), start_csq(), and status().

◆ _last_write_time

hrt_abstime IridiumSBD::_last_write_time = 0
private

Definition at line 333 of file IridiumSBD.h.

Referenced by standby_loop(), and write().

◆ _new_state

◆ _num_tx_buf_reset

uint16_t IridiumSBD::_num_tx_buf_reset = 0
private

Definition at line 303 of file IridiumSBD.h.

Referenced by publish_iridium_status(), and write().

◆ _packet_length

uint16_t IridiumSBD::_packet_length = 0
private

Definition at line 306 of file IridiumSBD.h.

Referenced by write().

◆ _param_read_interval_s

int32_t IridiumSBD::_param_read_interval_s = -1
private

Definition at line 295 of file IridiumSBD.h.

Referenced by main_loop(), and standby_loop().

◆ _param_session_timeout_s

int32_t IridiumSBD::_param_session_timeout_s = -1
private

Definition at line 296 of file IridiumSBD.h.

Referenced by main_loop(), and sbdsession_loop().

◆ _param_stacking_time_ms

int32_t IridiumSBD::_param_stacking_time_ms = -1
private

Definition at line 297 of file IridiumSBD.h.

Referenced by main_loop(), and standby_loop().

◆ _ring_pending

bool IridiumSBD::_ring_pending = false
private

Definition at line 326 of file IridiumSBD.h.

Referenced by publish_iridium_status(), read_at(), sbdsession_loop(), and start_sbd_session().

◆ _rx_buf_mutex

pthread_mutex_t IridiumSBD::_rx_buf_mutex = pthread_mutex_t()
private

Definition at line 342 of file IridiumSBD.h.

Referenced by main_loop(), read(), and read_rx_buf().

◆ _rx_command_buf

uint8_t IridiumSBD::_rx_command_buf[SATCOM_RX_COMMAND_BUF_LEN] = {}
private

◆ _rx_command_len

int IridiumSBD::_rx_command_len = 0
private

Definition at line 316 of file IridiumSBD.h.

Referenced by read_at_command(), start_test(), and test_loop().

◆ _rx_msg_buf

uint8_t IridiumSBD::_rx_msg_buf[SATCOM_RX_MSG_BUF_LEN] = {}
private

Definition at line 318 of file IridiumSBD.h.

Referenced by read(), read_at_msg(), and read_rx_buf().

◆ _rx_msg_end_idx

int IridiumSBD::_rx_msg_end_idx = 0
private

◆ _rx_msg_read_idx

int IridiumSBD::_rx_msg_read_idx = 0
private

Definition at line 320 of file IridiumSBD.h.

Referenced by ioctl(), poll_state(), publish_iridium_status(), read(), read_rx_buf(), and standby_loop().

◆ _rx_read_pending

bool IridiumSBD::_rx_read_pending = false
private

◆ _rx_session_pending

bool IridiumSBD::_rx_session_pending = false
private

Definition at line 327 of file IridiumSBD.h.

Referenced by publish_iridium_status(), read_at(), sbdsession_loop(), standby_loop(), and status().

◆ _session_start_time

hrt_abstime IridiumSBD::_session_start_time = 0
private

Definition at line 336 of file IridiumSBD.h.

Referenced by sbdsession_loop(), and start_sbd_session().

◆ _signal_quality

uint8_t IridiumSBD::_signal_quality = 0
private

Definition at line 300 of file IridiumSBD.h.

Referenced by csq_loop(), publish_iridium_status(), sbdsession_loop(), standby_loop(), and status().

◆ _start_completed

bool IridiumSBD::_start_completed = false
private

Definition at line 292 of file IridiumSBD.h.

Referenced by main_loop(), and start().

◆ _state

satcom_state IridiumSBD::_state = SATCOM_STATE_STANDBY
private

◆ _status

iridiumsbd_status_s IridiumSBD::_status = {}
private

Definition at line 346 of file IridiumSBD.h.

Referenced by publish_iridium_status(), and publish_subsystem_status().

◆ _subsystem_pub

uORB::PublicationQueued<subsystem_info_s> IridiumSBD::_subsystem_pub {ORB_ID(subsystem_info)}
private

Definition at line 309 of file IridiumSBD.h.

Referenced by publish_subsystem_status().

◆ _successful_sbd_sessions

uint16_t IridiumSBD::_successful_sbd_sessions = 0
private

Definition at line 302 of file IridiumSBD.h.

Referenced by publish_iridium_status(), and sbdsession_loop().

◆ _task_should_exit

bool IridiumSBD::_task_should_exit = false
private

Definition at line 291 of file IridiumSBD.h.

Referenced by main_loop(), start(), and stop().

◆ _test_command

char IridiumSBD::_test_command[32]
private

Definition at line 312 of file IridiumSBD.h.

Referenced by standby_loop(), start_test(), and test().

◆ _test_pending

bool IridiumSBD::_test_pending = false
private

Definition at line 311 of file IridiumSBD.h.

Referenced by schedule_test(), standby_loop(), and test().

◆ _test_timer

hrt_abstime IridiumSBD::_test_timer = 0
private

Definition at line 313 of file IridiumSBD.h.

Referenced by standby_loop(), and test_loop().

◆ _tx_buf

uint8_t IridiumSBD::_tx_buf[SATCOM_TX_BUF_LEN] = {}
private

Definition at line 322 of file IridiumSBD.h.

Referenced by write(), and write_tx_buf().

◆ _tx_buf_mutex

pthread_mutex_t IridiumSBD::_tx_buf_mutex = pthread_mutex_t()
private

Definition at line 341 of file IridiumSBD.h.

Referenced by main_loop(), sbdsession_loop(), start_sbd_session(), write(), and write_tx_buf().

◆ _tx_buf_write_idx

int IridiumSBD::_tx_buf_write_idx = 0
private

◆ _tx_buf_write_pending

bool IridiumSBD::_tx_buf_write_pending = false
private

Definition at line 325 of file IridiumSBD.h.

Referenced by publish_iridium_status(), standby_loop(), write(), and write_tx_buf().

◆ _tx_session_pending

bool IridiumSBD::_tx_session_pending = false
private

◆ _verbose

bool IridiumSBD::_verbose = false
private

Definition at line 344 of file IridiumSBD.h.

Referenced by main_loop().

◆ _writing_mavlink_packet

bool IridiumSBD::_writing_mavlink_packet = false
private

Definition at line 305 of file IridiumSBD.h.

Referenced by write().

◆ instance

IridiumSBD * IridiumSBD::instance
staticprivate

Definition at line 289 of file IridiumSBD.h.

Referenced by main_loop_helper(), status(), stop(), and test().

◆ task_handle

int IridiumSBD::task_handle
staticprivate

Definition at line 290 of file IridiumSBD.h.

Referenced by main_loop_helper(), start(), and stop().

◆ uart_fd

int IridiumSBD::uart_fd = -1
private

Definition at line 293 of file IridiumSBD.h.

Referenced by main_loop_helper(), open_uart(), read_at(), stop(), write_at(), and write_tx_buf().


The documentation for this class was generated from the following files: