mavlink_dialect.h
Go to the documentation of this file.
00001 
00009 /*
00010  * libmavconn
00011  * Copyright 2014,2015 Vladimir Ermakov, All rights reserved.
00012  *
00013  * This file is part of the mavros package and subject to the license terms
00014  * in the top-level LICENSE file of the mavros repository.
00015  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
00016  */
00017 
00018 #pragma once
00019 
00020 #if !defined(MAVLINK_DIALECT)
00021 # define MAVLINK_DIALECT common
00022 # warning "No MAVLINK_DIALECT specified. fallback to " MAVLINK_DIALECT
00023 #endif
00024 
00025 /* Do not use default inlined mavlink functions!
00026  * Issue #269
00027  */
00028 #define MAVLINK_GET_CHANNEL_STATUS
00029 #define MAVLINK_GET_CHANNEL_BUFFER
00030 
00031 // include common types before dialect only needed for these overridden functions
00032 #include <mavlink/v1.0/mavlink_types.h>
00033 
00034 // definition in mavlink_helpers.cpp
00035 extern "C" mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
00036 extern "C" mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);
00037 
00038 /* C preprocessor could not compare strings directly
00039  * See: http://c-faq.com/cpp/ifstrcmp.html
00040  */
00041 #define _DIALECT(name)          _DIALECT_CONCAT(name)
00042 #define _DIALECT_CONCAT(name)   _DIALECT_ ## name
00043 #define _DIALECT_ardupilotmega  1
00044 #define _DIALECT_autoquad       2
00045 #define _DIALECT_common         3
00046 #define _DIALECT_matrixpilot    4
00047 #define _DIALECT_minimal        5
00048 #define _DIALECT_pixhawk        6       /* removed */
00049 #define _DIALECT_slugs          7
00050 #define _DIALECT_test           8
00051 #define _DIALECT_ualberta       9
00052 #define _DIALECT_sensesoar      10      /* removed */
00053 #define _DIALECT_ASLUAV         11
00054 #define _DIALECT_paparazzi      12
00055 
00056 #  if _DIALECT(MAVLINK_DIALECT) == _DIALECT_ardupilotmega
00057 #  include <mavlink/v1.0/ardupilotmega/mavlink.h>
00058 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_autoquad
00059 #  include <mavlink/v1.0/autoquad/mavlink.h>
00060 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_common
00061 #  include <mavlink/v1.0/common/mavlink.h>
00062 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_matrixpilot
00063 #  include <mavlink/v1.0/matrixpilot/mavlink.h>
00064 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_minimal
00065 #  include <mavlink/v1.0/minimal/mavlink.h>
00066 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_pixhawk
00067 #  include <mavlink/v1.0/pixhawk/mavlink.h>
00068 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_slugs
00069 #  include <mavlink/v1.0/slugs/mavlink.h>
00070 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_test
00071 #  include <mavlink/v1.0/test/mavlink.h>
00072 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_ualberta
00073 #  include <mavlink/v1.0/ualberta/mavlink.h>
00074 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_sensesoar
00075 #  include <mavlink/v1.0/sensesoar/mavlink.h>
00076 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_ASLUAV
00077 #  include <mavlink/v1.0/ASLUAV/mavlink.h>
00078 #elif _DIALECT(MAVLINK_DIALECT) == _DIALECT_paparazzi
00079 #  include <mavlink/v1.0/paparazzi/mavlink.h>
00080 #else
00081 #  error "Unknown MAVLINK_DIALECT"
00082 #endif
00083 


libmavconn
Author(s): Vladimir Ermakov
autogenerated on Thu Feb 9 2017 04:00:13