mavlink_dialect.h
Go to the documentation of this file.
00001 
00009 /*
00010  * Copyright 2014 Vladimir Ermakov.
00011  *
00012  * This program is free software; you can redistribute it and/or modify
00013  * it under the terms of the GNU General Public License as published by
00014  * the Free Software Foundation; either version 3 of the License, or
00015  * (at your option) any later version.
00016  *
00017  * This program is distributed in the hope that it will be useful, but
00018  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
00019  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
00020  * for more details.
00021  *
00022  * You should have received a copy of the GNU General Public License along
00023  * with this program; if not, write to the Free Software Foundation, Inc.,
00024  * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
00025  */
00026 
00027 #pragma once
00028 
00029 #if !defined(MAVLINK_DIALECT)
00030 # define MAVLINK_DIALECT common
00031 # warning "No MAVLINK_DIALECT specified. fallback to " MAVLINK_DIALECT
00032 #endif
00033 
00034 /* C preprocessor could not compare strings directly
00035  * See: http://c-faq.com/cpp/ifstrcmp.html
00036  */
00037 #define _DIALECT(name)          _DIALECT_CONCAT(name)
00038 #define _DIALECT_CONCAT(name)   _DIALECT_ ## name
00039 #define _DIALECT_ardupilotmega  1
00040 #define _DIALECT_autoquad       2
00041 #define _DIALECT_common         3
00042 #define _DIALECT_matrixpilot    4
00043 #define _DIALECT_minimal        5
00044 #define _DIALECT_pixhawk        6
00045 #define _DIALECT_slugs          7
00046 #define _DIALECT_test           8
00047 #define _DIALECT_ualberta       9
00048 #define _DIALECT_sensesoar      10
00049 
00050 #  if _DIALECT(MAVLINK_DIALECT) == _DIALECT_ardupilotmega
00051 #  include <mavlink/v1.0/ardupilotmega/mavlink.h>
00052 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_autoquad
00053 #  include <mavlink/v1.0/autoquad/mavlink.h>
00054 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_common
00055 #  include <mavlink/v1.0/common/mavlink.h>
00056 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_matrixpilot
00057 #  include <mavlink/v1.0/matrixpilot/mavlink.h>
00058 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_minimal
00059 #  include <mavlink/v1.0/minimal/mavlink.h>
00060 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_pixhawk
00061 #  include <mavlink/v1.0/pixhawk/mavlink.h>
00062 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_slugs
00063 #  include <mavlink/v1.0/slugs/mavlink.h>
00064 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_test
00065 #  include <mavlink/v1.0/test/mavlink.h>
00066 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_ualberta
00067 #  include <mavlink/v1.0/ualberta/mavlink.h>
00068 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_sensesoar
00069 #  include <mavlink/v1.0/sensesoar/mavlink.h>
00070 #else
00071 #  error "Unknown MAVLINK_DIALECT"
00072 #endif
00073 


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:08