32 #ifndef ROSFLIGHT_FIRMWARE_MAVLINK_H 33 #define ROSFLIGHT_FIRMWARE_MAVLINK_H 35 #pragma GCC diagnostic push 36 #pragma GCC diagnostic ignored "-Wpedantic" 37 #pragma GCC diagnostic ignored "-Wswitch-default" 38 #pragma GCC diagnostic ignored "-Wcast-align" 39 #pragma GCC diagnostic ignored "-Wignored-qualifiers" 40 #pragma GCC diagnostic ignored "-Wpragmas" 41 #pragma GCC diagnostic ignored "-Waddress-of-packed-member" 43 #pragma GCC diagnostic pop 57 void init(uint32_t baud_rate, uint32_t dev)
override;
61 uint64_t timestamp_us,
66 void send_diff_pressure(uint8_t system_id,
float velocity,
float pressure,
float temperature)
override;
69 uint64_t timestamp_us,
72 float temperature)
override;
76 void send_named_value_float(uint8_t system_id, uint32_t timestamp_ms,
const char *
const name,
float value)
override;
77 void send_output_raw(uint8_t system_id, uint32_t timestamp_ms,
const float raw_outputs[14])
override;
80 const char *
const name,
82 uint16_t param_count)
override;
85 const char *
const name,
87 uint16_t param_count)
override;
88 void send_rc_raw(uint8_t system_id, uint32_t timestamp_ms,
const uint16_t
channels[8])
override;
93 float min_range)
override;
100 uint8_t control_mode,
102 int16_t loop_time_us)
override;
103 void send_timesync(uint8_t system_id, int64_t tc1, int64_t ts1)
override;
104 void send_version(uint8_t system_id,
const char *
const version)
override;
107 void send_error_data(uint8_t system_id,
const StateManager::BackupData &error_data)
override;
138 #endif // ROSFLIGHT_FIRMWARE_MAVLINK_H void handle_msg_timesync(const mavlink_message_t *const msg)
void handle_msg_offboard_control(const mavlink_message_t *const msg)
static volatile int16_t gyro[3]
void send_version(uint8_t system_id, const char *const version) override
void send_mag(uint8_t system_id, const turbomath::Vector &mag) override
void send_heartbeat(uint8_t system_id, bool fixed_wing) override
mavlink_message_t in_buf_
void set_listener(ListenerInterface *listener) override
void send_diff_pressure(uint8_t system_id, float velocity, float pressure, float temperature) override
void send_timesync(uint8_t system_id, int64_t tc1, int64_t ts1) override
void send_baro(uint8_t system_id, float altitude, float pressure, float temperature) override
void handle_msg_external_attitude(const mavlink_message_t *const msg)
void send_attitude_quaternion(uint8_t system_id, uint64_t timestamp_us, const turbomath::Quaternion &attitude, const turbomath::Vector &angular_velocity) 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 handle_msg_rosflight_cmd(const mavlink_message_t *const msg)
void handle_mavlink_message()
void send_gnss(uint8_t system_id, const GNSSData &data) override
void send_sonar(uint8_t system_id, uint8_t type, float range, float max_range, float min_range) override
void send_message(const mavlink_message_t &msg)
MAVLink comm protocol built from rosflight.xml.
ListenerInterface * listener_
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_battery_status(uint8_t system_id, float voltage, float current) override
void send_gnss_full(uint8_t system_id, const GNSSFull &full) override
void send_error_data(uint8_t system_id, const StateManager::BackupData &error_data) override
static volatile int16_t accel[3]
ROSLIB_DECL std::string command(const std::string &cmd)
static const channelConfig_t channels[CC_CHANNELS_PER_TIMER]
void send_named_value_int(uint8_t system_id, uint32_t timestamp_ms, const char *const name, int32_t value) override
void handle_msg_rosflight_aux_cmd(const mavlink_message_t *const msg)
void init(uint32_t baud_rate, uint32_t dev) override
void send_named_value_float(uint8_t system_id, uint32_t timestamp_ms, const char *const name, float value) override
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_heartbeat(const mavlink_message_t *const msg)
void send_log_message(uint8_t system_id, LogSeverity severity, const char *text) override
void send_rc_raw(uint8_t system_id, uint32_t timestamp_ms, const uint16_t channels[8]) 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_output_raw(uint8_t system_id, uint32_t timestamp_ms, const float raw_outputs[14]) override
void handle_msg_param_set(const mavlink_message_t *const msg)
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_command_ack(uint8_t system_id, Command command, bool success) override