Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rosflight_firmware::CommManager Class Reference

#include <comm_manager.h>

Inheritance diagram for rosflight_firmware::CommManager:
Inheritance graph
[legend]

Classes

class  LogMessageBuffer
 
class  Stream
 

Public Member Functions

 CommManager (ROSflight &rf, CommLinkInterface &comm_link)
 
void init ()
 
void log (CommLinkInterface::LogSeverity severity, const char *fmt,...)
 
void param_change_callback (uint16_t param_id) override
 
void receive (void)
 
void send_backup_data (const StateManager::BackupData &backup_data)
 
void send_named_value_float (const char *const name, float value)
 
void send_param_value (uint16_t param_id)
 
void send_parameter_list ()
 
void set_streaming_rate (uint8_t stream_id, int16_t param_id)
 
void stream ()
 
void update_status ()
 

Private Types

enum  OffboardControlMode { MODE_PASS_THROUGH, MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE, MODE_ROLL_PITCH_YAWRATE_THROTTLE, MODE_ROLL_PITCH_YAWRATE_ALTITUDE }
 
enum  StreamId {
  STREAM_ID_HEARTBEAT, STREAM_ID_STATUS, STREAM_ID_ATTITUDE, STREAM_ID_IMU,
  STREAM_ID_DIFF_PRESSURE, STREAM_ID_BARO, STREAM_ID_SONAR, STREAM_ID_MAG,
  STREAM_ID_BATTERY_STATUS, STREAM_ID_SERVO_OUTPUT_RAW, STREAM_ID_GNSS, STREAM_ID_GNSS_FULL,
  STREAM_ID_RC_RAW, STREAM_ID_LOW_PRIORITY, STREAM_COUNT
}
 

Private Member Functions

void aux_command_callback (const CommLinkInterface::AuxCommand &command) override
 
void command_callback (CommLinkInterface::Command command) override
 
void external_attitude_callback (const turbomath::Quaternion &q) override
 
void heartbeat_callback () override
 
void offboard_control_callback (const CommLinkInterface::OffboardControl &control) override
 
void param_request_list_callback (uint8_t target_system) override
 
void param_request_read_callback (uint8_t target_system, const char *const param_name, int16_t param_index) override
 
void param_set_float_callback (uint8_t target_system, const char *const param_name, float param_value) override
 
void param_set_int_callback (uint8_t target_system, const char *const param_name, int32_t param_value) override
 
void send_attitude (void)
 
void send_baro (void)
 
void send_battery_status (void)
 
void send_diff_pressure (void)
 
void send_gnss (void)
 
void send_gnss_full (void)
 
void send_heartbeat (void)
 
void send_imu (void)
 
void send_low_priority (void)
 
void send_mag (void)
 
void send_named_value_int (const char *const name, int32_t value)
 
void send_next_param (void)
 
void send_output_raw (void)
 
void send_rc_raw (void)
 
void send_sonar (void)
 
void send_status (void)
 
void timesync_callback (int64_t tc1, int64_t ts1) override
 
void update_system_id (uint16_t param_id)
 

Private Attributes

StateManager::BackupData backup_data_buffer_
 
CommLinkInterfacecomm_link_
 
bool connected_ = false
 
bool have_backup_data_ = false
 
bool initialized_ = false
 
uint32_t last_sent_gnss_full_tow_ = 0
 
uint32_t last_sent_gnss_tow_ = 0
 
LogMessageBuffer log_buffer_
 
uint64_t offboard_control_time_
 
ROSflightRF_
 
uint8_t send_params_index_
 
Stream streams_ [STREAM_COUNT]
 
uint8_t sysid_
 

Static Private Attributes

static constexpr int LOG_MSG_SIZE = 50
 

Detailed Description

Definition at line 47 of file comm_manager.h.

Member Enumeration Documentation

Enumerator
MODE_PASS_THROUGH 
MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE 
MODE_ROLL_PITCH_YAWRATE_THROTTLE 
MODE_ROLL_PITCH_YAWRATE_ALTITUDE 

Definition at line 72 of file comm_manager.h.

Enumerator
STREAM_ID_HEARTBEAT 
STREAM_ID_STATUS 
STREAM_ID_ATTITUDE 
STREAM_ID_IMU 
STREAM_ID_DIFF_PRESSURE 
STREAM_ID_BARO 
STREAM_ID_SONAR 
STREAM_ID_MAG 
STREAM_ID_BATTERY_STATUS 
STREAM_ID_SERVO_OUTPUT_RAW 
STREAM_ID_GNSS 
STREAM_ID_GNSS_FULL 
STREAM_ID_RC_RAW 
STREAM_ID_LOW_PRIORITY 
STREAM_COUNT 

Definition at line 50 of file comm_manager.h.

Constructor & Destructor Documentation

rosflight_firmware::CommManager::CommManager ( ROSflight rf,
CommLinkInterface comm_link 
)

Definition at line 74 of file comm_manager.cpp.

Member Function Documentation

void rosflight_firmware::CommManager::aux_command_callback ( const CommLinkInterface::AuxCommand command)
overrideprivatevirtual
void rosflight_firmware::CommManager::command_callback ( CommLinkInterface::Command  command)
overrideprivatevirtual
void rosflight_firmware::CommManager::external_attitude_callback ( const turbomath::Quaternion q)
overrideprivatevirtual
void rosflight_firmware::CommManager::heartbeat_callback ( void  )
overrideprivatevirtual

JSJ: I don't think we need this

Implements rosflight_firmware::CommLinkInterface::ListenerInterface.

Definition at line 381 of file comm_manager.cpp.

void rosflight_firmware::CommManager::init ( )

Definition at line 77 of file comm_manager.cpp.

void rosflight_firmware::CommManager::log ( CommLinkInterface::LogSeverity  severity,
const char *  fmt,
  ... 
)

Definition at line 405 of file comm_manager.cpp.

void rosflight_firmware::CommManager::offboard_control_callback ( const CommLinkInterface::OffboardControl control)
overrideprivatevirtual
void rosflight_firmware::CommManager::param_change_callback ( uint16_t  param_id)
overridevirtual

Implements rosflight_firmware::ParamListenerInterface.

Definition at line 103 of file comm_manager.cpp.

void rosflight_firmware::CommManager::param_request_list_callback ( uint8_t  target_system)
overrideprivatevirtual
void rosflight_firmware::CommManager::param_request_read_callback ( uint8_t  target_system,
const char *const  param_name,
int16_t  param_index 
)
overrideprivatevirtual
void rosflight_firmware::CommManager::param_set_float_callback ( uint8_t  target_system,
const char *const  param_name,
float  param_value 
)
overrideprivatevirtual
void rosflight_firmware::CommManager::param_set_int_callback ( uint8_t  target_system,
const char *const  param_name,
int32_t  param_value 
)
overrideprivatevirtual
void rosflight_firmware::CommManager::receive ( void  )

Definition at line 400 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_attitude ( void  )
private

Definition at line 448 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_backup_data ( const StateManager::BackupData &  backup_data)

Definition at line 520 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_baro ( void  )
private

Definition at line 490 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_battery_status ( void  )
private

Definition at line 514 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_diff_pressure ( void  )
private

Definition at line 481 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_gnss ( void  )
private

Definition at line 533 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_gnss_full ( void  )
private

Definition at line 547 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_heartbeat ( void  )
private

Definition at line 424 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_imu ( void  )
private

Definition at line 454 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_low_priority ( void  )
private

Definition at line 561 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_mag ( void  )
private

Definition at line 509 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_named_value_float ( const char *const  name,
float  value 
)

Definition at line 595 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_named_value_int ( const char *const  name,
int32_t  value 
)
private

Definition at line 590 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_next_param ( void  )
private

Definition at line 600 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_output_raw ( void  )
private

Definition at line 462 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_param_value ( uint16_t  param_id)

Definition at line 165 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_parameter_list ( )

Definition at line 191 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_rc_raw ( void  )
private

Definition at line 467 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_sonar ( void  )
private

Definition at line 499 of file comm_manager.cpp.

void rosflight_firmware::CommManager::send_status ( void  )
private

Definition at line 429 of file comm_manager.cpp.

void rosflight_firmware::CommManager::set_streaming_rate ( uint8_t  stream_id,
int16_t  param_id 
)

Definition at line 585 of file comm_manager.cpp.

void rosflight_firmware::CommManager::stream ( )

Definition at line 575 of file comm_manager.cpp.

void rosflight_firmware::CommManager::timesync_callback ( int64_t  tc1,
int64_t  ts1 
)
overrideprivatevirtual
void rosflight_firmware::CommManager::update_status ( )

Definition at line 160 of file comm_manager.cpp.

void rosflight_firmware::CommManager::update_system_id ( uint16_t  param_id)
private

Definition at line 155 of file comm_manager.cpp.

Member Data Documentation

StateManager::BackupData rosflight_firmware::CommManager::backup_data_buffer_
private

Definition at line 115 of file comm_manager.h.

CommLinkInterface& rosflight_firmware::CommManager::comm_link_
private

Definition at line 83 of file comm_manager.h.

bool rosflight_firmware::CommManager::connected_ = false
private

Definition at line 86 of file comm_manager.h.

bool rosflight_firmware::CommManager::have_backup_data_ = false
private

Definition at line 116 of file comm_manager.h.

bool rosflight_firmware::CommManager::initialized_ = false
private

Definition at line 85 of file comm_manager.h.

uint32_t rosflight_firmware::CommManager::last_sent_gnss_full_tow_ = 0
private

Definition at line 176 of file comm_manager.h.

uint32_t rosflight_firmware::CommManager::last_sent_gnss_tow_ = 0
private

Definition at line 175 of file comm_manager.h.

LogMessageBuffer rosflight_firmware::CommManager::log_buffer_
private

Definition at line 113 of file comm_manager.h.

constexpr int rosflight_firmware::CommManager::LOG_MSG_SIZE = 50
staticprivate

Definition at line 88 of file comm_manager.h.

uint64_t rosflight_firmware::CommManager::offboard_control_time_
private

Definition at line 81 of file comm_manager.h.

ROSflight& rosflight_firmware::CommManager::RF_
private

Definition at line 82 of file comm_manager.h.

uint8_t rosflight_firmware::CommManager::send_params_index_
private

Definition at line 84 of file comm_manager.h.

Stream rosflight_firmware::CommManager::streams_[STREAM_COUNT]
private
Initial value:
= {
Stream(0, [this] { this->send_heartbeat(); }), Stream(0, [this] { this->send_status(); }),
Stream(0, [this] { this->send_attitude(); }), Stream(0, [this] { this->send_imu(); }),
Stream(0, [this] { this->send_diff_pressure(); }), Stream(0, [this] { this->send_baro(); }),
Stream(0, [this] { this->send_sonar(); }), Stream(0, [this] { this->send_mag(); }),
Stream(0, [this] { this->send_battery_status(); }), Stream(0, [this] { this->send_output_raw(); }),
Stream(0, [this] { this->send_gnss(); }), Stream(0, [this] { this->send_gnss_full(); }),
Stream(0, [this] { this->send_rc_raw(); }), Stream(20000, [this] { this->send_low_priority(); })}

Definition at line 165 of file comm_manager.h.

uint8_t rosflight_firmware::CommManager::sysid_
private

Definition at line 80 of file comm_manager.h.


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


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:58