mavlink.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef ROSFLIGHT_FIRMWARE_MAVLINK_H
33 #define ROSFLIGHT_FIRMWARE_MAVLINK_H
34 
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"
42 #include "v1.0/rosflight/mavlink.h"
43 #pragma GCC diagnostic pop
44 
45 #include "interface/comm_link.h"
46 
47 #include "board.h"
48 
49 namespace rosflight_firmware
50 {
51 class Board;
52 
53 class Mavlink : public CommLinkInterface
54 {
55 public:
56  Mavlink(Board &board);
57  void init(uint32_t baud_rate, uint32_t dev) override;
58  void receive() override;
59 
60  void send_attitude_quaternion(uint8_t system_id,
61  uint64_t timestamp_us,
62  const turbomath::Quaternion &attitude,
63  const turbomath::Vector &angular_velocity) override;
64  void send_baro(uint8_t system_id, float altitude, float pressure, float temperature) override;
65  void send_command_ack(uint8_t system_id, Command command, bool success) override;
66  void send_diff_pressure(uint8_t system_id, float velocity, float pressure, float temperature) override;
67  void send_heartbeat(uint8_t system_id, bool fixed_wing) override;
68  void send_imu(uint8_t system_id,
69  uint64_t timestamp_us,
70  const turbomath::Vector &accel,
71  const turbomath::Vector &gyro,
72  float temperature) override;
73  void send_log_message(uint8_t system_id, LogSeverity severity, const char *text) override;
74  void send_mag(uint8_t system_id, const turbomath::Vector &mag) override;
75  void send_named_value_int(uint8_t system_id, uint32_t timestamp_ms, const char *const name, int32_t value) 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;
78  void send_param_value_int(uint8_t system_id,
79  uint16_t index,
80  const char *const name,
81  int32_t value,
82  uint16_t param_count) override;
83  void send_param_value_float(uint8_t system_id,
84  uint16_t index,
85  const char *const name,
86  float value,
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;
89  void send_sonar(uint8_t system_id,
90  /* TODO enum type*/ uint8_t type,
91  float range,
92  float max_range,
93  float min_range) override;
94  void send_status(uint8_t system_id,
95  bool armed,
96  bool failsafe,
97  bool rc_override,
98  bool offboard,
99  uint8_t error_code,
100  uint8_t control_mode,
101  int16_t num_errors,
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;
105  void send_gnss(uint8_t system_id, const GNSSData &data) override;
106  void send_gnss_full(uint8_t system_id, const GNSSFull &full) override;
107  void send_error_data(uint8_t system_id, const StateManager::BackupData &error_data) override;
108  void send_battery_status(uint8_t system_id, float voltage, float current) override;
109 
110  inline void set_listener(ListenerInterface *listener) override { listener_ = listener; }
111 
112 private:
113  void send_message(const mavlink_message_t &msg);
114 
115  void handle_msg_param_request_list(const mavlink_message_t *const msg);
116  void handle_msg_param_request_read(const mavlink_message_t *const msg);
117  void handle_msg_param_set(const mavlink_message_t *const msg);
118  void handle_msg_offboard_control(const mavlink_message_t *const msg);
119  void handle_msg_external_attitude(const mavlink_message_t *const msg);
120  void handle_msg_rosflight_cmd(const mavlink_message_t *const msg);
121  void handle_msg_rosflight_aux_cmd(const mavlink_message_t *const msg);
122  void handle_msg_timesync(const mavlink_message_t *const msg);
123  void handle_msg_heartbeat(const mavlink_message_t *const msg);
124  void handle_mavlink_message();
125 
127 
128  uint32_t compid_ = 250;
129  mavlink_message_t in_buf_;
131  bool initialized_ = false;
132 
134 };
135 
136 } // namespace rosflight_firmware
137 
138 #endif // ROSFLIGHT_FIRMWARE_MAVLINK_H
static volatile int16_t gyro[3]
Definition: drv_mpu6050.c:277
float altitude
Definition: ms4525.c:41
float pressure
Definition: ms4525.c:41
float temperature
Definition: ms4525.c:41
static volatile int16_t accel[3]
Definition: drv_mpu6050.c:276
ROSLIB_DECL std::string command(const std::string &cmd)
static const channelConfig_t channels[CC_CHANNELS_PER_TIMER]
Definition: drv_timer.c:111


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