Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer_ros/tf_bridge.h"
00018
00019 #include "absl/memory/memory.h"
00020 #include "cartographer_ros/msg_conversion.h"
00021
00022 namespace cartographer_ros {
00023
00024 TfBridge::TfBridge(const std::string& tracking_frame,
00025 const double lookup_transform_timeout_sec,
00026 const tf2_ros::Buffer* buffer)
00027 : tracking_frame_(tracking_frame),
00028 lookup_transform_timeout_sec_(lookup_transform_timeout_sec),
00029 buffer_(buffer) {}
00030
00031 std::unique_ptr<::cartographer::transform::Rigid3d> TfBridge::LookupToTracking(
00032 const ::cartographer::common::Time time,
00033 const std::string& frame_id) const {
00034 ::ros::Duration timeout(lookup_transform_timeout_sec_);
00035 std::unique_ptr<::cartographer::transform::Rigid3d> frame_id_to_tracking;
00036 try {
00037 const ::ros::Time latest_tf_time =
00038 buffer_
00039 ->lookupTransform(tracking_frame_, frame_id, ::ros::Time(0.),
00040 timeout)
00041 .header.stamp;
00042 const ::ros::Time requested_time = ToRos(time);
00043 if (latest_tf_time >= requested_time) {
00044
00045
00046 timeout = ::ros::Duration(0.);
00047 }
00048 return absl::make_unique<::cartographer::transform::Rigid3d>(
00049 ToRigid3d(buffer_->lookupTransform(tracking_frame_, frame_id,
00050 requested_time, timeout)));
00051 } catch (const tf2::TransformException& ex) {
00052 LOG(WARNING) << ex.what();
00053 }
00054 return nullptr;
00055 }
00056
00057 }