Public Member Functions | Private Member Functions | Private Attributes | List of all members
rosflight_firmware::Mavlink Class Reference

#include <mavlink.h>

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

Public Member Functions

void init (uint32_t baud_rate, uint32_t dev) override
 
 Mavlink (Board &board)
 
void receive () override
 
void send_attitude_quaternion (uint8_t system_id, uint64_t timestamp_us, const turbomath::Quaternion &attitude, const turbomath::Vector &angular_velocity) override
 
void send_baro (uint8_t system_id, float altitude, float pressure, float temperature) override
 
void send_battery_status (uint8_t system_id, float voltage, float current) override
 
void send_command_ack (uint8_t system_id, Command command, bool success) override
 
void send_diff_pressure (uint8_t system_id, float velocity, float pressure, float temperature) override
 
void send_error_data (uint8_t system_id, const StateManager::BackupData &error_data) override
 
void send_gnss (uint8_t system_id, const GNSSData &data) override
 
void send_gnss_full (uint8_t system_id, const GNSSFull &full) override
 
void send_heartbeat (uint8_t system_id, bool fixed_wing) override
 
void send_imu (uint8_t system_id, uint64_t timestamp_us, const turbomath::Vector &accel, const turbomath::Vector &gyro, float temperature) override
 
void send_log_message (uint8_t system_id, LogSeverity severity, const char *text) override
 
void send_mag (uint8_t system_id, const turbomath::Vector &mag) override
 
void send_named_value_float (uint8_t system_id, uint32_t timestamp_ms, const char *const name, float value) override
 
void send_named_value_int (uint8_t system_id, uint32_t timestamp_ms, const char *const name, int32_t value) override
 
void send_output_raw (uint8_t system_id, uint32_t timestamp_ms, const float raw_outputs[14]) override
 
void send_param_value_float (uint8_t system_id, uint16_t index, const char *const name, float value, uint16_t param_count) override
 
void send_param_value_int (uint8_t system_id, uint16_t index, const char *const name, int32_t value, uint16_t param_count) override
 
void send_rc_raw (uint8_t system_id, uint32_t timestamp_ms, const uint16_t channels[8]) override
 
void send_sonar (uint8_t system_id, uint8_t type, float range, float max_range, float min_range) override
 
void send_status (uint8_t system_id, bool armed, bool failsafe, bool rc_override, bool offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) override
 
void send_timesync (uint8_t system_id, int64_t tc1, int64_t ts1) override
 
void send_version (uint8_t system_id, const char *const version) override
 
void set_listener (ListenerInterface *listener) override
 

Private Member Functions

void handle_mavlink_message ()
 
void handle_msg_external_attitude (const mavlink_message_t *const msg)
 
void handle_msg_heartbeat (const mavlink_message_t *const msg)
 
void handle_msg_offboard_control (const mavlink_message_t *const msg)
 
void handle_msg_param_request_list (const mavlink_message_t *const msg)
 
void handle_msg_param_request_read (const mavlink_message_t *const msg)
 
void handle_msg_param_set (const mavlink_message_t *const msg)
 
void handle_msg_rosflight_aux_cmd (const mavlink_message_t *const msg)
 
void handle_msg_rosflight_cmd (const mavlink_message_t *const msg)
 
void handle_msg_timesync (const mavlink_message_t *const msg)
 
void send_message (const mavlink_message_t &msg)
 

Private Attributes

Boardboard_
 
uint32_t compid_ = 250
 
mavlink_message_t in_buf_
 
bool initialized_ = false
 
ListenerInterfacelistener_ = nullptr
 
mavlink_status_t status_
 

Additional Inherited Members

- Public Types inherited from rosflight_firmware::CommLinkInterface
enum  Command {
  Command::COMMAND_READ_PARAMS, Command::COMMAND_WRITE_PARAMS, Command::COMMAND_SET_PARAM_DEFAULTS, Command::COMMAND_ACCEL_CALIBRATION,
  Command::COMMAND_GYRO_CALIBRATION, Command::COMMAND_BARO_CALIBRATION, Command::COMMAND_AIRSPEED_CALIBRATION, Command::COMMAND_RC_CALIBRATION,
  Command::COMMAND_REBOOT, Command::COMMAND_REBOOT_TO_BOOTLOADER, Command::COMMAND_SEND_VERSION
}
 
enum  LogSeverity { LogSeverity::LOG_INFO, LogSeverity::LOG_WARNING, LogSeverity::LOG_ERROR, LogSeverity::LOG_CRITICAL }
 

Detailed Description

Definition at line 53 of file mavlink.h.

Constructor & Destructor Documentation

rosflight_firmware::Mavlink::Mavlink ( Board board)

Definition at line 39 of file mavlink.cpp.

Member Function Documentation

void rosflight_firmware::Mavlink::handle_mavlink_message ( )
private

Definition at line 544 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_external_attitude ( const mavlink_message_t *const  msg)
private

Definition at line 520 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_heartbeat ( const mavlink_message_t *const  msg)
private

Definition at line 535 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_offboard_control ( const mavlink_message_t *const  msg)
private

Definition at line 484 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_param_request_list ( const mavlink_message_t *const  msg)
private

Definition at line 344 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_param_request_read ( const mavlink_message_t *const  msg)
private

Definition at line 353 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_param_set ( const mavlink_message_t *const  msg)
private

Definition at line 362 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_rosflight_aux_cmd ( const mavlink_message_t *const  msg)
private

Definition at line 440 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_rosflight_cmd ( const mavlink_message_t *const  msg)
private

Definition at line 387 of file mavlink.cpp.

void rosflight_firmware::Mavlink::handle_msg_timesync ( const mavlink_message_t *const  msg)
private

Definition at line 475 of file mavlink.cpp.

void rosflight_firmware::Mavlink::init ( uint32_t  baud_rate,
uint32_t  dev 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 41 of file mavlink.cpp.

void rosflight_firmware::Mavlink::receive ( void  )
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 47 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_attitude_quaternion ( uint8_t  system_id,
uint64_t  timestamp_us,
const turbomath::Quaternion attitude,
const turbomath::Vector angular_velocity 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 56 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_baro ( uint8_t  system_id,
float  altitude,
float  pressure,
float  temperature 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 68 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_battery_status ( uint8_t  system_id,
float  voltage,
float  current 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 327 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_command_ack ( uint8_t  system_id,
Command  command,
bool  success 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 75 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_diff_pressure ( uint8_t  system_id,
float  velocity,
float  pressure,
float  temperature 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 121 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_error_data ( uint8_t  system_id,
const StateManager::BackupData &  error_data 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 319 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_gnss ( uint8_t  system_id,
const GNSSData data 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 147 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_gnss_full ( uint8_t  system_id,
const GNSSFull full 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 157 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_heartbeat ( uint8_t  system_id,
bool  fixed_wing 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 128 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_imu ( uint8_t  system_id,
uint64_t  timestamp_us,
const turbomath::Vector accel,
const turbomath::Vector gyro,
float  temperature 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 136 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_log_message ( uint8_t  system_id,
LogSeverity  severity,
const char *  text 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 192 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_mag ( uint8_t  system_id,
const turbomath::Vector mag 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 216 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_message ( const mavlink_message_t &  msg)
private

Definition at line 334 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_named_value_float ( uint8_t  system_id,
uint32_t  timestamp_ms,
const char *const  name,
float  value 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 230 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_named_value_int ( uint8_t  system_id,
uint32_t  timestamp_ms,
const char *const  name,
int32_t  value 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 223 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_output_raw ( uint8_t  system_id,
uint32_t  timestamp_ms,
const float  raw_outputs[14] 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 237 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_param_value_float ( uint8_t  system_id,
uint16_t  index,
const char *const  name,
float  value,
uint16_t  param_count 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 258 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_param_value_int ( uint8_t  system_id,
uint16_t  index,
const char *const  name,
int32_t  value,
uint16_t  param_count 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 244 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_rc_raw ( uint8_t  system_id,
uint32_t  timestamp_ms,
const uint16_t  channels[8] 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 269 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_sonar ( uint8_t  system_id,
uint8_t  type,
float  range,
float  max_range,
float  min_range 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 278 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_status ( uint8_t  system_id,
bool  armed,
bool  failsafe,
bool  rc_override,
bool  offboard,
uint8_t  error_code,
uint8_t  control_mode,
int16_t  num_errors,
int16_t  loop_time_us 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 290 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_timesync ( uint8_t  system_id,
int64_t  tc1,
int64_t  ts1 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 306 of file mavlink.cpp.

void rosflight_firmware::Mavlink::send_version ( uint8_t  system_id,
const char *const  version 
)
overridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 313 of file mavlink.cpp.

void rosflight_firmware::Mavlink::set_listener ( ListenerInterface listener)
inlineoverridevirtual

Implements rosflight_firmware::CommLinkInterface.

Definition at line 110 of file mavlink.h.

Member Data Documentation

Board& rosflight_firmware::Mavlink::board_
private

Definition at line 126 of file mavlink.h.

uint32_t rosflight_firmware::Mavlink::compid_ = 250
private

Definition at line 128 of file mavlink.h.

mavlink_message_t rosflight_firmware::Mavlink::in_buf_
private

Definition at line 129 of file mavlink.h.

bool rosflight_firmware::Mavlink::initialized_ = false
private

Definition at line 131 of file mavlink.h.

ListenerInterface* rosflight_firmware::Mavlink::listener_ = nullptr
private

Definition at line 133 of file mavlink.h.

mavlink_status_t rosflight_firmware::Mavlink::status_
private

Definition at line 130 of file mavlink.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