56 const std::string& target_frame,
const std::string& source_frame,
57 const cyber::Time& time,
const float timeout_second = 0.01f)
const;
76 const std::string& target_frame,
const cyber::Time& target_time,
77 const std::string& source_frame,
const cyber::Time& source_time,
78 const std::string& fixed_frame,
const float timeout_second = 0.01f)
const;
89 virtual bool canTransform(
const std::string& target_frame,
90 const std::string& source_frame,
92 const float timeout_second = 0.01f,
93 std::string* errstr =
nullptr)
const;
107 virtual bool canTransform(
const std::string& target_frame,
109 const std::string& source_frame,
111 const std::string& fixed_frame,
112 const float timeout_second = 0.01f,
113 std::string* errstr =
nullptr)
const;
116 const std::string& child_frame_id,
120 void SubscriptionCallback(
121 const std::shared_ptr<const TransformStampeds>&
transform);
122 void StaticSubscriptionCallback(
123 const std::shared_ptr<const TransformStampeds>& transform);
124 void SubscriptionCallbackImpl(
125 const std::shared_ptr<const TransformStampeds>& transform,
128 void TF2MsgToCyber(
const geometry_msgs::TransformStamped& tf2_trans_stamped,
131 std::unique_ptr<cyber::Node> node_;
132 std::shared_ptr<cyber::Reader<TransformStampeds>> message_subscriber_tf_;
133 std::shared_ptr<cyber::Reader<TransformStampeds>>
134 message_subscriber_tf_static_;
137 std::vector<geometry_msgs::TransformStamped> static_msgs_;