Program Listing for File macros.hpp
↰ Return to documentation for file (include/ros_babel_fish/macros.hpp
)
// Copyright (c) 2020 Stefan Fabian. All rights reserved.
// Licensed under the MIT license. See LICENSE file in the project root for full license information.
#ifndef ROS_BABEL_FISH_MACROS_HPP
#define ROS_BABEL_FISH_MACROS_HPP
#include "ros_babel_fish/messages/message_type_traits.hpp"
#define RBF2_TEMPLATE_CALL( function, type, ... ) \
do { \
switch ( type ) { \
case MessageTypes::Compound: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Compound>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Array: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Array>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Bool: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Bool>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Octet: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Octet>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt8: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt16: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt32: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt64: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int8: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int16: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int32: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int64: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Float: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Float>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Double: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Double>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::LongDouble: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::LongDouble>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Char: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Char>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::WChar: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::WChar>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::String: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::String>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::WString: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::WString>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::None: \
break; /* Do nothing except tell the compiler we know about this type. */ \
} \
} while ( false )
#define RBF2_TEMPLATE_CALL_VALUE_TYPES( function, type, ... ) \
do { \
switch ( type ) { \
case MessageTypes::Bool: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Bool>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Octet: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Octet>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt8: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt16: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt32: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt64: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int8: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int16: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int32: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int64: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Float: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Float>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Double: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Double>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::LongDouble: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::LongDouble>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Char: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::Char>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::WChar: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::WChar>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::String: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::String>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::WString: \
function<::ros_babel_fish::message_type_traits::value_type<MessageTypes::WString>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Array: \
case MessageTypes::Compound: \
case MessageTypes::None: \
break; /* Do nothing except tell the compiler we know about these types. */ \
} \
} while ( false )
#define RBF2_TEMPLATE_CALL_SIMPLE_VALUE_TYPES( function, type, ... ) \
do { \
switch ( type ) { \
case MessageTypes::Bool: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Bool>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Octet: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Octet>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt8: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt16: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt32: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::UInt64: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int8: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int8>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int16: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int16>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int32: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int32>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Int64: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int64>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Float: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Float>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Double: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Double>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::LongDouble: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::LongDouble>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::Char: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Char>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::WChar: \
function<typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::WChar>::value>( \
__VA_ARGS__ ); \
break; \
case MessageTypes::String: \
case MessageTypes::WString: \
case MessageTypes::Array: \
case MessageTypes::Compound: \
case MessageTypes::None: \
break; /* Do nothing except tell the compiler we know about these types. */ \
} \
} while ( false )
#define _RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( FUNCTION, ... ) FUNCTION( __VA_ARGS__ )
#define _RBF2_TEMPLATE_CALL_ARRAY_TYPES( FUNCTION, ARRAY, BOUNDED, FIXEDLENGTH, ... ) \
switch ( ARRAY.elementType() ) { \
case MessageTypes::Bool: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Bool>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Octet: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Octet>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::UInt8: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt8>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::UInt16: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt16>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::UInt32: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt32>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::UInt64: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::UInt64>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Int8: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int8>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Int16: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int16>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Int32: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int32>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Int64: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Int64>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Float: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Float>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Double: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Double>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::LongDouble: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::LongDouble>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Char: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::Char>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::WChar: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::WChar>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::String: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::String>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::WString: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<typename ::ros_babel_fish::ArrayMessage_< \
typename ::ros_babel_fish::message_type_traits::value_type<MessageTypes::WString>::value, \
BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) __VA_ARGS__ ); \
break; \
case MessageTypes::Compound: \
_RBF2_TEMPLATE_CALL_ARRAY_FUNCTION( \
FUNCTION, \
(ARRAY.as<::ros_babel_fish::CompoundArrayMessage_<BOUNDED, FIXEDLENGTH>>())__VA_OPT__(, ) \
__VA_ARGS__ ); \
break; \
case MessageTypes::Array: \
case MessageTypes::None: \
break; /* Do nothing except tell the compiler we know about these types. */ \
}
#define RBF2_TEMPLATE_CALL_ARRAY_TYPES( FUNCTION, ARRAY, ... ) \
do { \
static_assert( \
::std::is_same<::ros_babel_fish::ArrayMessageBase, \
std::remove_const<std::remove_reference<decltype( ARRAY )>::type>::type>::value, \
"Second argument to macro needs to be of type ArrayMessageBase!" ); \
if ( ( ARRAY ).isFixedSize() ) { \
_RBF2_TEMPLATE_CALL_ARRAY_TYPES( FUNCTION, ( ARRAY ), true, true, __VA_ARGS__ ) \
} else if ( ( ARRAY ).isBounded() ) { \
_RBF2_TEMPLATE_CALL_ARRAY_TYPES( FUNCTION, ( ARRAY ), true, false, __VA_ARGS__ ) \
} else { \
_RBF2_TEMPLATE_CALL_ARRAY_TYPES( FUNCTION, ( ARRAY ), false, false, __VA_ARGS__ ) \
} \
} while ( false )
#endif // ROS_BABEL_FISH_MACROS_HPP