MAV'RIC
|
00001 /******************************************************************************* 00002 * Copyright (c) 2009-2016, MAV'RIC Development Team 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * 1. Redistributions of source code must retain the above copyright notice, 00009 * this list of conditions and the following disclaimer. 00010 * 00011 * 2. Redistributions in binary form must reproduce the above copyright notice, 00012 * this list of conditions and the following disclaimer in the documentation 00013 * and/or other materials provided with the distribution. 00014 * 00015 * 3. Neither the name of the copyright holder nor the names of its contributors 00016 * may be used to endorse or promote products derived from this software without 00017 * specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 ******************************************************************************/ 00031 00032 /******************************************************************************* 00033 * \file mavlink_communication.hpp 00034 * 00035 * \author MAV'RIC Team 00036 * \author Julien Lecoeur 00037 * 00038 * \brief This module handles various aspect of mavlink protocol with periodic telemetry, 00039 * message callback, and onboard parameters 00040 * 00041 ******************************************************************************/ 00042 00043 00044 #ifndef MAVLINK_COMMUNICATION_HPP_ 00045 #define MAVLINK_COMMUNICATION_HPP_ 00046 00047 #include "communication/mavlink_stream.hpp" 00048 #include "communication/periodic_telemetry.hpp" 00049 #include "communication/onboard_parameters.hpp" 00050 #include "communication/mavlink_message_handler.hpp" 00051 00052 00057 template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM> 00058 class Mavlink_communication_T 00059 { 00060 public: 00061 00065 struct conf_t 00066 { 00067 Mavlink_stream::conf_t mavlink_stream; 00068 Periodic_telemetry::conf_t telemetry; 00069 Mavlink_message_handler::conf_t handler; 00070 Onboard_parameters::conf_t parameters; 00071 }; 00072 00080 static inline conf_t default_config(uint8_t sysid = 1) 00081 { 00082 conf_t conf = {}; 00083 00084 conf.mavlink_stream = {}; 00085 conf.mavlink_stream.sysid = sysid; 00086 conf.mavlink_stream.compid = 50; 00087 conf.mavlink_stream.debug = false, 00088 00089 conf.telemetry = Periodic_telemetry::default_config(); 00090 conf.handler = Mavlink_message_handler::default_config(); 00091 conf.parameters = Onboard_parameters::default_config(); 00092 00093 return conf; 00094 }; 00095 00106 Mavlink_communication_T(Serial& serial, State& state, File& file_storage, const conf_t& config = default_config()): 00107 mavlink_stream_(serial, config.mavlink_stream), 00108 handler_(mavlink_stream_, config.handler), 00109 telemetry_(mavlink_stream_, handler_, config.telemetry), 00110 parameters_(file_storage, state, handler_, mavlink_stream_, config.parameters) 00111 {} 00112 00119 uint32_t sysid() 00120 { 00121 return mavlink_stream_.sysid(); 00122 } 00123 00124 00125 /* 00126 * \brief Returns periodic telemetry 00127 */ 00128 Periodic_telemetry& telemetry() 00129 { 00130 return telemetry_; 00131 } 00132 00133 /* 00134 * \brief Returns message_handler 00135 */ 00136 Mavlink_message_handler& handler() 00137 { 00138 return handler_; 00139 } 00140 00141 /* 00142 * \brief Returns mavlink_stream 00143 */ 00144 Mavlink_stream& mavlink_stream() 00145 { 00146 return mavlink_stream_; 00147 } 00148 00149 /* 00150 * \brief Returns onboard_parameters struct 00151 */ 00152 Onboard_parameters& parameters() 00153 { 00154 return parameters_; 00155 } 00156 00157 00163 bool update(void) 00164 { 00165 // Receive new message 00166 Mavlink_stream::msg_received_t rec; 00167 while (mavlink_stream_.receive(&rec)) 00168 { 00169 handler_.receive(&rec); 00170 } 00171 00172 // Send messages 00173 telemetry_.update(); 00174 00175 // Send one onboard param, if necessary 00176 parameters_.send_first_scheduled_parameter(); 00177 00178 return true; 00179 } 00180 00181 00189 static bool update_task(Mavlink_communication_T* mavlink_communication) 00190 { 00191 return mavlink_communication->update(); 00192 } 00193 00194 private: 00195 Mavlink_stream mavlink_stream_; 00196 Mavlink_message_handler_T<N_MSG_CB, N_CMD_CB> handler_; 00197 Periodic_telemetry_T<N_TELEM> telemetry_; 00198 Onboard_parameters_T<N_PARAM> parameters_; 00199 }; 00200 00201 00202 #endif /* MAVLINK_COMMUNICATION_HPP_ */