tf_bridge.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H
19 
20 #include <memory>
21 
23 #include "tf2_ros/buffer.h"
24 
26 
27 namespace cartographer_ros {
28 
29 class TfBridge {
30  public:
31  TfBridge(const std::string& tracking_frame,
32  double lookup_transform_timeout_sec, const tf2_ros::Buffer* buffer);
33  ~TfBridge() {}
34 
35  TfBridge(const TfBridge&) = delete;
36  TfBridge& operator=(const TfBridge&) = delete;
37 
38  // Returns the transform for 'frame_id' to 'tracking_frame_' if it exists at
39  // 'time'.
40  std::unique_ptr<::cartographer::transform::Rigid3d> LookupToTracking(
41  ::cartographer::common::Time time, const std::string& frame_id) const;
42 
43  private:
44  const std::string tracking_frame_;
46  const tf2_ros::Buffer* const buffer_;
47 };
48 
49 } // namespace cartographer_ros
50 
51 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TF_BRIDGE_H
TfBridge & operator=(const TfBridge &)=delete
TfBridge(const std::string &tracking_frame, double lookup_transform_timeout_sec, const tf2_ros::Buffer *buffer)
Definition: tf_bridge.cc:24
const tf2_ros::Buffer *const buffer_
Definition: tf_bridge.h:46
const common::Time time
UniversalTimeScaleClock::time_point Time
std::unique_ptr<::cartographer::transform::Rigid3d > LookupToTracking(::cartographer::common::Time time, const std::string &frame_id) const
Definition: tf_bridge.cc:31
const std::string tracking_frame_
Definition: tf_bridge.h:44
const double lookup_transform_timeout_sec_
Definition: tf_bridge.h:45


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05