Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[foxy] gazebo_ros: Add inline keyword to template definitions (#1367) #1389

Open
wants to merge 1 commit into
base: foxy
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ namespace gazebo_ros
/// \param[in] in Gazebo Time to convert.
/// \return A ROS Time message with the same value as in
template<>
inline
builtin_interfaces::msg::Time Convert(const gazebo::common::Time & in)
{
builtin_interfaces::msg::Time time;
Expand All @@ -40,6 +41,7 @@ builtin_interfaces::msg::Time Convert(const gazebo::common::Time & in)
/// \param[in] in Gazebo Time message to convert.
/// \return A ROS Time message with the same value as in
template<>
inline
builtin_interfaces::msg::Time Convert(const gazebo::msgs::Time & in)
{
builtin_interfaces::msg::Time time;
Expand All @@ -53,6 +55,7 @@ builtin_interfaces::msg::Time Convert(const gazebo::msgs::Time & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const builtin_interfaces::msg::Time &)
{
T::ConversionNotImplemented;
Expand All @@ -62,6 +65,7 @@ T Convert(const builtin_interfaces::msg::Time &)
/// \param[in] in ROS Time message to convert.
/// \return A Gazebo Time with the same value as in
template<>
inline
gazebo::common::Time Convert(const builtin_interfaces::msg::Time & in)
{
gazebo::common::Time time;
Expand All @@ -75,6 +79,7 @@ gazebo::common::Time Convert(const builtin_interfaces::msg::Time & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const builtin_interfaces::msg::Duration &)
{
T::ConversionNotImplemented;
Expand All @@ -84,6 +89,7 @@ T Convert(const builtin_interfaces::msg::Duration &)
/// \param[in] in ROS Time message to convert.
/// \return A Gazebo Time with the same value as in
template<>
inline
gazebo::common::Time Convert(const builtin_interfaces::msg::Duration & in)
{
gazebo::common::Time time;
Expand Down
2 changes: 2 additions & 0 deletions gazebo_ros/include/gazebo_ros/conversions/gazebo_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ namespace gazebo_ros
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const gazebo::msgs::Contacts &)
{
T::ConversionNotImplemented;
Expand All @@ -41,6 +42,7 @@ T Convert(const gazebo::msgs::Contacts &)
/// \param[in] in Input message;
/// \return A ROS Contacts state message with the same data as the input message
template<>
inline
gazebo_msgs::msg::ContactsState Convert(const gazebo::msgs::Contacts & in)
{
gazebo_msgs::msg::ContactsState contact_state_msg;
Expand Down
6 changes: 6 additions & 0 deletions gazebo_ros/include/gazebo_ros/conversions/generic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ static rclcpp::Logger conversions_logger = rclcpp::get_logger("gazebo_ros_conver
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const ignition::math::Vector3d &)
{
T::ConversionNotImplemented;
Expand All @@ -45,6 +46,7 @@ T Convert(const ignition::math::Vector3d &)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const ignition::math::Quaterniond &)
{
T::ConversionNotImplemented;
Expand All @@ -55,6 +57,7 @@ T Convert(const ignition::math::Quaterniond &)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const ignition::math::Pose3d &)
{
T::ConversionNotImplemented;
Expand All @@ -65,6 +68,7 @@ T Convert(const ignition::math::Pose3d &)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const gazebo::common::Time &)
{
T::ConversionNotImplemented;
Expand All @@ -74,6 +78,7 @@ T Convert(const gazebo::common::Time &)
/// \param[in] in Gazebo Time to convert.
/// \return A rclcpp::Time object with the same value as in
template<>
inline
rclcpp::Time Convert(const gazebo::common::Time & in)
{
return rclcpp::Time(in.sec, in.nsec, rcl_clock_type_t::RCL_ROS_TIME);
Expand All @@ -84,6 +89,7 @@ rclcpp::Time Convert(const gazebo::common::Time & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const gazebo::msgs::Time &)
{
T::ConversionNotImplemented;
Expand Down
19 changes: 19 additions & 0 deletions gazebo_ros/include/gazebo_ros/conversions/geometry_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ namespace gazebo_ros
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Vector3 &)
{
T::ConversionNotImplemented;
Expand All @@ -44,6 +45,7 @@ T Convert(const geometry_msgs::msg::Vector3 &)
/// \param[in] msg ROS message to convert.
/// \return An Ignition Math vector.
template<>
inline
ignition::math::Vector3d Convert(const geometry_msgs::msg::Vector3 & msg)
{
ignition::math::Vector3d vec;
Expand All @@ -58,6 +60,7 @@ ignition::math::Vector3d Convert(const geometry_msgs::msg::Vector3 & msg)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Point32 &)
{
T::ConversionNotImplemented;
Expand All @@ -67,6 +70,7 @@ T Convert(const geometry_msgs::msg::Point32 &)
/// \param[in] in ROS message to convert.
/// \return An Ignition Math vector.
template<>
inline
ignition::math::Vector3d Convert(const geometry_msgs::msg::Point32 & in)
{
ignition::math::Vector3d vec;
Expand All @@ -81,6 +85,7 @@ ignition::math::Vector3d Convert(const geometry_msgs::msg::Point32 & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Point &)
{
T::ConversionNotImplemented;
Expand All @@ -91,6 +96,7 @@ T Convert(const geometry_msgs::msg::Point &)
/// \param[in] in ROS message to convert.
/// \return A ROS vector message.
template<>
inline
geometry_msgs::msg::Vector3 Convert(const geometry_msgs::msg::Point & in)
{
geometry_msgs::msg::Vector3 msg;
Expand All @@ -104,6 +110,7 @@ geometry_msgs::msg::Vector3 Convert(const geometry_msgs::msg::Point & in)
/// \param[in] in ROS message to convert.
/// \return A ROS vector message.
template<>
inline
ignition::math::Vector3d Convert(const geometry_msgs::msg::Point & in)
{
ignition::math::Vector3d out;
Expand All @@ -117,6 +124,7 @@ ignition::math::Vector3d Convert(const geometry_msgs::msg::Point & in)
/// \param[in] vec Ignition vector to convert.
/// \return ROS geometry vector message
template<>
inline
geometry_msgs::msg::Vector3 Convert(const ignition::math::Vector3d & vec)
{
geometry_msgs::msg::Vector3 msg;
Expand All @@ -130,6 +138,7 @@ geometry_msgs::msg::Vector3 Convert(const ignition::math::Vector3d & vec)
/// \param[in] vec Ignition vector to convert.
/// \return ROS geometry point message
template<>
inline
geometry_msgs::msg::Point Convert(const ignition::math::Vector3d & vec)
{
geometry_msgs::msg::Point msg;
Expand All @@ -143,6 +152,7 @@ geometry_msgs::msg::Point Convert(const ignition::math::Vector3d & vec)
/// \param[in] in Ignition Quaternion to convert.
/// \return ROS geometry quaternion message
template<>
inline
geometry_msgs::msg::Quaternion Convert(const ignition::math::Quaterniond & in)
{
geometry_msgs::msg::Quaternion msg;
Expand All @@ -157,6 +167,7 @@ geometry_msgs::msg::Quaternion Convert(const ignition::math::Quaterniond & in)
/// \param[in] in Ignition Pose3d to convert.
/// \return ROS geometry transform message
template<>
inline
geometry_msgs::msg::Transform Convert(const ignition::math::Pose3d & in)
{
geometry_msgs::msg::Transform msg;
Expand All @@ -169,6 +180,7 @@ geometry_msgs::msg::Transform Convert(const ignition::math::Pose3d & in)
/// \param[in] in Ignition Pose3d to convert.
/// \return ROS geometry pose message
template<>
inline
geometry_msgs::msg::Pose Convert(const ignition::math::Pose3d & in)
{
geometry_msgs::msg::Pose msg;
Expand All @@ -182,6 +194,7 @@ geometry_msgs::msg::Pose Convert(const ignition::math::Pose3d & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Quaternion &)
{
T::ConversionNotImplemented;
Expand All @@ -191,6 +204,7 @@ T Convert(const geometry_msgs::msg::Quaternion &)
/// \param[in] in Input quaternion message
/// \return Ignition math quaternion with same values as the input message
template<>
inline
ignition::math::Quaterniond Convert(const geometry_msgs::msg::Quaternion & in)
{
return ignition::math::Quaterniond(in.w, in.x, in.y, in.z);
Expand All @@ -201,6 +215,7 @@ ignition::math::Quaterniond Convert(const geometry_msgs::msg::Quaternion & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Transform &)
{
T::ConversionNotImplemented;
Expand All @@ -210,6 +225,7 @@ T Convert(const geometry_msgs::msg::Transform &)
/// \param[in] in ROS message to convert.
/// \return A Ignition Math pose3d.
template<>
inline
ignition::math::Pose3d Convert(const geometry_msgs::msg::Transform & in)
{
ignition::math::Pose3d msg;
Expand All @@ -223,6 +239,7 @@ ignition::math::Pose3d Convert(const geometry_msgs::msg::Transform & in)
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const geometry_msgs::msg::Pose &)
{
T::ConversionNotImplemented;
Expand All @@ -232,6 +249,7 @@ T Convert(const geometry_msgs::msg::Pose &)
/// \param[in] in ROS pose message to convert.
/// \return A ROS geometry transform message.
template<>
inline
geometry_msgs::msg::Transform Convert(const geometry_msgs::msg::Pose & in)
{
geometry_msgs::msg::Transform msg;
Expand All @@ -244,6 +262,7 @@ geometry_msgs::msg::Transform Convert(const geometry_msgs::msg::Pose & in)
/// \param[in] in ROS pose message to convert.
/// \return Ignition Math pose.
template<>
inline
ignition::math::Pose3d Convert(const geometry_msgs::msg::Pose & in)
{
return {Convert<ignition::math::Vector3d>(in.position),
Expand Down
5 changes: 5 additions & 0 deletions gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ namespace gazebo_ros
/// \return Conversion result
/// \tparam T Output type
template<class T>
inline
T Convert(const gazebo::msgs::LaserScanStamped &, double min_intensity = 0.0)
{
(void)min_intensity;
Expand All @@ -53,6 +54,7 @@ T Convert(const gazebo::msgs::LaserScanStamped &, double min_intensity = 0.0)
/// \note If multiple vertical rays are present, the LaserScan will be the
/// horizontal scan in the center of the vertical range
template<>
inline
sensor_msgs::msg::LaserScan Convert(const gazebo::msgs::LaserScanStamped & in, double min_intensity)
{
sensor_msgs::msg::LaserScan ls;
Expand Down Expand Up @@ -95,6 +97,7 @@ sensor_msgs::msg::LaserScan Convert(const gazebo::msgs::LaserScanStamped & in, d
/// \param[in] min_intensity The minimum intensity value to clip the output intensities
/// \return A ROS PointCloud message with the same data as the input message
template<>
inline
sensor_msgs::msg::PointCloud Convert(
const gazebo::msgs::LaserScanStamped & in,
double min_intensity)
Expand Down Expand Up @@ -178,6 +181,7 @@ sensor_msgs::msg::PointCloud Convert(
/// \param[in] min_intensity The minimum intensity value to clip the output intensities
/// \return A ROS PointCloud2 message with the same data as the input message
template<>
inline
sensor_msgs::msg::PointCloud2 Convert(
const gazebo::msgs::LaserScanStamped & in,
double min_intensity)
Expand Down Expand Up @@ -283,6 +287,7 @@ sensor_msgs::msg::PointCloud2 Convert(
/// \param[in] min_intensity Ignored.
/// \return A ROS Range message with minimum range of the rays in the laser scan
template<>
inline
sensor_msgs::msg::Range Convert(const gazebo::msgs::LaserScanStamped & in, double min_intensity)
{
(void) min_intensity;
Expand Down