Skip to content

Commit

Permalink
fix syntax issue with gcc (#1674)
Browse files Browse the repository at this point in the history
* fix syntax issue with gcc

Signed-off-by: William Woodall <william@osrfoundation.org>

* uncrustify

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed May 15, 2021
1 parent f245b4c commit 18fcd91
Showing 1 changed file with 7 additions and 3 deletions.
10 changes: 7 additions & 3 deletions rclcpp/include/rclcpp/type_adapter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,18 +179,22 @@ struct TypeAdapter<T, void, std::enable_if_t<ImplicitTypeAdapter<T>::is_speciali

/// Assigns the custom type implicitly to the given custom type/ros message type pair.
/**
* Note: this macro needs to be used in the root namespace.
* We cannot use ::rclcpp to protect against this, due to how GCC interprets the
* syntax, see: https://stackoverflow.com/a/2781537
*
* \sa TypeAdapter
* \sa ImplicitTypeAdapter
*/
#define RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(CustomType, ROSMessageType) \
template<> \
struct ::rclcpp::ImplicitTypeAdapter<CustomType> \
: public ::rclcpp::TypeAdapter<CustomType, ROSMessageType> \
struct rclcpp::ImplicitTypeAdapter<CustomType> \
: public rclcpp::TypeAdapter<CustomType, ROSMessageType> \
{ \
static_assert( \
is_specialized::value, \
"Cannot use custom type as ros type when there is no TypeAdapter for that pair"); \
};
}

} // namespace rclcpp

Expand Down

0 comments on commit 18fcd91

Please sign in to comment.