.. _program_listing_file__tmp_ws_src_gazebo_ros_pkgs_gazebo_ros_include_gazebo_ros_conversions_generic.hpp: Program Listing for File generic.hpp ==================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/gazebo_ros_pkgs/gazebo_ros/include/gazebo_ros/conversions/generic.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2018 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef GAZEBO_ROS__CONVERSIONS__GENERIC_HPP_ #define GAZEBO_ROS__CONVERSIONS__GENERIC_HPP_ #include #include #include #include #include #include #include #include namespace gazebo_ros { static rclcpp::Logger conversions_logger = rclcpp::get_logger("gazebo_ros_conversions"); template inline T Convert(const ignition::math::Vector3d &) { T::ConversionNotImplemented; } template inline T Convert(const ignition::math::Quaterniond &) { T::ConversionNotImplemented; } template inline T Convert(const ignition::math::Pose3d &) { T::ConversionNotImplemented; } template inline T Convert(const gazebo::common::Time &) { T::ConversionNotImplemented; } template<> inline rclcpp::Time Convert(const gazebo::common::Time & in) { return rclcpp::Time(in.sec, in.nsec, rcl_clock_type_t::RCL_ROS_TIME); } template inline T Convert(const gazebo::msgs::Time &) { T::ConversionNotImplemented; } } // namespace gazebo_ros #endif // GAZEBO_ROS__CONVERSIONS__GENERIC_HPP_