25 const double lookup_transform_timeout_sec,
27 : tracking_frame_(tracking_frame),
28 lookup_transform_timeout_sec_(lookup_transform_timeout_sec),
32 const ::cartographer::common::Time time,
const string& frame_id)
const {
34 std::unique_ptr<::cartographer::transform::Rigid3d> frame_id_to_tracking;
36 const ::ros::Time latest_tf_time =
41 const ::ros::Time requested_time =
ToRos(time);
42 if (latest_tf_time >= requested_time) {
47 return ::cartographer::common::make_unique<
51 LOG(WARNING) << ex.what();
const tf2_ros::Buffer *const buffer_
std::unique_ptr<::cartographer::transform::Rigid3d > LookupToTracking(::cartographer::common::Time time, const string &frame_id) const
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)
const string tracking_frame_
::ros::Time ToRos(::cartographer::common::Time time)
const double lookup_transform_timeout_sec_