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 #include "v1.0/rosflight/mavlink.h"
40 # pragma GCC diagnostic pop
41 
42 #include "comm_link.h"
43 #include "board.h"
44 
45 namespace rosflight_firmware
46 {
47 
48 class Board;
49 
50 class Mavlink : public CommLink
51 {
52 public:
53  Mavlink(Board &board);
54  void init(uint32_t baud_rate, uint32_t dev) override;
55  void receive() override;
56 
57  void send_attitude_quaternion(uint8_t system_id,
58  uint64_t timestamp_us,
59  const turbomath::Quaternion &attitude,
60  const turbomath::Vector &angular_velocity) override;
61  void send_baro(uint8_t system_id, float altitude, float pressure, float temperature) override;
62  void send_command_ack(uint8_t system_id, Command command, bool success) override;
63  void send_diff_pressure(uint8_t system_id, float velocity, float pressure, float temperature) override;
64  void send_heartbeat(uint8_t system_id, bool fixed_wing) override;
65  void send_imu(uint8_t system_id, uint64_t timestamp_us,
66  const turbomath::Vector &accel,
67  const turbomath::Vector &gyro,
68  float temperature) override;
69  void send_log_message(uint8_t system_id, LogSeverity severity, const char *text) override;
70  void send_mag(uint8_t system_id, const turbomath::Vector &mag) override;
71  void send_named_value_int(uint8_t system_id, uint32_t timestamp_ms, const char *const name, int32_t value) override;
72  void send_named_value_float(uint8_t system_id, uint32_t timestamp_ms, const char *const name, float value) override;
73  void send_output_raw(uint8_t system_id, uint32_t timestamp_ms, const float raw_outputs[8]) override;
74  void send_param_value_int(uint8_t system_id,
75  uint16_t index,
76  const char *const name,
77  int32_t value,
78  uint16_t param_count) override;
79  void send_param_value_float(uint8_t system_id,
80  uint16_t index,
81  const char *const name,
82  float value,
83  uint16_t param_count) override;
84  void send_rc_raw(uint8_t system_id, uint32_t timestamp_ms, const uint16_t channels[8]) override;
85  void send_sonar(uint8_t system_id, /* TODO enum type*/uint8_t type, float range, float max_range,
86  float min_range) override;
87  void send_status(uint8_t system_id,
88  bool armed,
89  bool failsafe,
90  bool rc_override,
91  bool offboard,
92  uint8_t error_code,
93  uint8_t control_mode,
94  int16_t num_errors,
95  int16_t loop_time_us) override;
96  void send_timesync(uint8_t system_id, int64_t tc1, int64_t ts1) override;
97  void send_version(uint8_t system_id, const char *const version) override;
98  virtual void send_gnss(uint8_t system_id, uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos,
99  int32_t lat,
100  int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc,
101  int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y,
102  int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp);
103  void send_gnss_raw(uint8_t system_id, uint32_t time_of_week, uint16_t year, uint8_t month, uint8_t day,
104  uint8_t hour, uint8_t min, uint8_t sec, uint8_t valid, uint32_t t_acc,
105  int32_t nano, uint8_t fix_type, uint8_t num_sat,
106  int32_t lon, int32_t lat, int32_t height, int32_t height_msl,
107  uint32_t h_acc, uint32_t v_acc, int32_t vel_n, int32_t vel_e,
108  int32_t vel_d, int32_t g_speed, int32_t head_mot, uint32_t s_acc,
109  uint32_t head_acc, uint16_t p_dop, uint64_t rosflight_timestamp);
110  void send_error_data(uint8_t system_id, const BackupData &error_data);
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_attitude_correction(const mavlink_message_t *const msg);
120  void handle_msg_rosflight_cmd(const mavlink_message_t *const msg);
121  void handle_msg_timesync(const mavlink_message_t *const msg);
122  void handle_msg_heartbeat(const mavlink_message_t *const msg);
123  void handle_mavlink_message(void);
124 
126 
127  uint32_t compid_ = 250;
128  mavlink_message_t in_buf_;
130  bool initialized_ = false;
131 };
132 
133 } // namespace rosflight_firmware
134 
135 #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 Wed Jul 3 2019 19:59:24