MAV'RIC
/home/travis/build/lis-epfl/MAVRIC_Library/communication/mavlink_message_handler.hpp
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_message_handler.hpp
00034  *
00035  * \author MAV'RIC Team
00036  * \author Julien Lecoeur
00037  *
00038  * \brief This module handles of all incoming MAVLink message by calling the
00039  * appropriate functions
00040  *
00041  ******************************************************************************/
00042 
00043 
00044 #ifndef MAVLINK_MESSAGE_HANDLING_HPP_
00045 #define MAVLINK_MESSAGE_HANDLING_HPP_
00046 
00047 #include "communication/mavlink_stream.hpp"
00048 
00049 #include "util/print_util.hpp"
00050 
00051 #define MAV_SYS_ID_ALL 0
00052 #define MAV_MSG_ENUM_END 255
00053 
00054 
00059 typedef enum MAV_RESULT mav_result_t;
00060 
00061 
00068 class Mavlink_message_handler
00069 {
00070 public:
00071 
00075     template<typename T>
00076     struct msg_function
00077     {
00078         typedef void (*type_t)(T*, uint32_t sysid, const mavlink_message_t*);
00079     };
00080 
00081 
00085     template<typename T>
00086     struct cmd_function
00087     {
00088         typedef mav_result_t (*type_t)(T*, const mavlink_command_long_t*);
00089     };
00090 
00091 
00096     typedef enum MAV_COMPONENT mav_component_t;
00097 
00098 
00102     struct conf_t
00103     {
00104         bool debug;                                                     
00105     };
00106 
00112     static inline conf_t default_config(void);
00113 
00114 
00122     Mavlink_message_handler(Mavlink_stream& mavlink_stream, const conf_t& config);
00123 
00138     template<typename T>
00139     bool add_msg_callback( uint8_t                          message_id,
00140                            uint8_t                          sysid_filter,
00141                            mav_component_t                  compid_filter,
00142                            typename msg_function<T>::type_t function,
00143                            T*                               module_struct);
00144 
00159     template<typename T>
00160     bool add_cmd_callback(  uint16_t                            command_id,
00161                             uint8_t                             sysid_filter,
00162                             mav_component_t                     compid_filter,
00163                             mav_component_t                     compid_target,
00164                             typename cmd_function<T>::type_t    function,
00165                             T*                                  module_struct);
00166 
00173     void receive(Mavlink_stream::msg_received_t* rec);
00174 
00181     static void msg_default_dbg(mavlink_message_t* msg);
00182 
00189     static void cmd_default_dbg(mavlink_command_long_t* cmd);
00190 
00191 protected:
00192 
00196     struct msg_callback_t
00197     {
00198         uint8_t                     message_id;                     
00199         uint8_t                     sysid_filter;                   
00200         mav_component_t             compid_filter;                  
00201         msg_function<void>::type_t  function;                       
00202         void*                       module_struct;                  
00203     };
00204 
00205 
00209     struct cmd_callback_t
00210     {
00211         uint16_t                    command_id;                     
00212         uint8_t                     sysid_filter;                   
00213         mav_component_t             compid_filter;                  
00214         mav_component_t             compid_target;                  
00215         cmd_function<void>::type_t  function;                       
00216         void*                       module_struct;                  
00217     };
00218 
00219 
00226     virtual uint32_t msg_callback_max_count(void) = 0;
00227 
00228 
00235     virtual uint32_t cmd_callback_max_count(void) = 0;
00236 
00237 
00244     virtual msg_callback_t* msg_callback_list(void) = 0;
00245 
00246 
00253     virtual cmd_callback_t* cmd_callback_list(void) = 0;
00254 
00255 
00256 private:
00257     Mavlink_stream& mavlink_stream_;        
00258     bool debug_;                            
00259     uint32_t msg_callback_count_;           
00260     uint32_t cmd_callback_count_;           
00261 
00262 
00269     void sort_latest_msg_callback();
00270 
00278     void sort_latest_cmd_callback();
00279 
00288     bool match_msg(msg_callback_t* msg_callback, mavlink_message_t* msg);
00289 
00299     bool match_cmd(cmd_callback_t* cmd_callback, mavlink_message_t* msg, mavlink_command_long_t* cmd);
00300 
00301 };
00302 
00303 
00310 template<uint32_t N, uint32_t P>
00311 class Mavlink_message_handler_T: public Mavlink_message_handler
00312 {
00313 public:
00314 
00322     Mavlink_message_handler_T(Mavlink_stream& mavlink_stream, const conf_t& config):
00323         Mavlink_message_handler(mavlink_stream, config)
00324     {}
00325 
00326 
00327 protected:
00328 
00334     uint32_t msg_callback_max_count(void)
00335     {
00336         return N;
00337     }
00338 
00339 
00345     uint32_t cmd_callback_max_count(void)
00346     {
00347         return P;
00348     }
00349 
00350 
00356     msg_callback_t* msg_callback_list(void)
00357     {
00358         return msg_callback_list_;
00359     }
00360 
00361 
00367     cmd_callback_t* cmd_callback_list(void)
00368     {
00369         return cmd_callback_list_;
00370     }
00371 
00372 
00373 private:
00374 
00375     uint32_t msg_callback_count_max_;           
00376     uint32_t cmd_callback_count_max_;           
00377     msg_callback_t msg_callback_list_[N];       
00378     cmd_callback_t cmd_callback_list_[P];       
00379 };
00380 
00381 
00387 Mavlink_message_handler::conf_t Mavlink_message_handler::default_config(void)
00388 {
00389     conf_t conf = {};
00390     conf.debug  = false;
00391     return conf;
00392 }
00393 
00394 #include "mavlink_message_handler.hxx"
00395 
00396 #endif /* MAVLINK_MESSAGE_HANDLING_H */
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines