00001 /* 00002 * Copyright 2016 The Cartographer Authors 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 * 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 */ 00016 00017 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H 00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H 00019 00020 #include <memory> 00021 00022 #include "cartographer/transform/rigid_transform.h" 00023 #include "cartographer_ros/time_conversion.h" 00024 #include "tf2_ros/buffer.h" 00025 00026 namespace cartographer_ros { 00027 00028 class TfBridge { 00029 public: 00030 TfBridge(const std::string& tracking_frame, 00031 double lookup_transform_timeout_sec, const tf2_ros::Buffer* buffer); 00032 ~TfBridge() {} 00033 00034 TfBridge(const TfBridge&) = delete; 00035 TfBridge& operator=(const TfBridge&) = delete; 00036 00037 // Returns the transform for 'frame_id' to 'tracking_frame_' if it exists at 00038 // 'time'. 00039 std::unique_ptr<::cartographer::transform::Rigid3d> LookupToTracking( 00040 ::cartographer::common::Time time, const std::string& frame_id) const; 00041 00042 private: 00043 const std::string tracking_frame_; 00044 const double lookup_transform_timeout_sec_; 00045 const tf2_ros::Buffer* const buffer_; 00046 }; 00047 00048 } // namespace cartographer_ros 00049 00050 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H