tf_bridge.cc
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 
18 
21 
22 namespace cartographer_ros {
23 
24 TfBridge::TfBridge(const string& tracking_frame,
25  const double lookup_transform_timeout_sec,
26  const tf2_ros::Buffer* buffer)
27  : tracking_frame_(tracking_frame),
28  lookup_transform_timeout_sec_(lookup_transform_timeout_sec),
29  buffer_(buffer) {}
30 
31 std::unique_ptr<::cartographer::transform::Rigid3d> TfBridge::LookupToTracking(
32  const ::cartographer::common::Time time, const string& frame_id) const {
34  std::unique_ptr<::cartographer::transform::Rigid3d> frame_id_to_tracking;
35  try {
36  const ::ros::Time latest_tf_time =
37  buffer_
38  ->lookupTransform(tracking_frame_, frame_id, ::ros::Time(0.),
39  timeout)
40  .header.stamp;
41  const ::ros::Time requested_time = ToRos(time);
42  if (latest_tf_time >= requested_time) {
43  // We already have newer data, so we do not wait. Otherwise, we would wait
44  // for the full 'timeout' even if we ask for data that is too old.
45  timeout = ::ros::Duration(0.);
46  }
47  return ::cartographer::common::make_unique<
49  tracking_frame_, frame_id, requested_time, timeout)));
50  } catch (const tf2::TransformException& ex) {
51  LOG(WARNING) << ex.what();
52  }
53  return nullptr;
54 }
55 
56 } // namespace cartographer_ros
const tf2_ros::Buffer *const buffer_
Definition: tf_bridge.h:46
std::unique_ptr<::cartographer::transform::Rigid3d > LookupToTracking(::cartographer::common::Time time, const string &frame_id) const
Definition: tf_bridge.cc:31
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
TfBridge(const string &tracking_frame, double lookup_transform_timeout_sec, const tf2_ros::Buffer *buffer)
Definition: tf_bridge.cc:24
const string tracking_frame_
Definition: tf_bridge.h:44
::ros::Time ToRos(::cartographer::common::Time time)
const double lookup_transform_timeout_sec_
Definition: tf_bridge.h:45


cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40