45 #include <boost/unordered_map.hpp>
46 #include <boost/signals2.hpp>
47 #include "geometry_msgs/TwistStamped.h"
53 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
54 #ifdef tf_EXPORTS // we are building a shared lib/dll
55 #define TF_DECL ROS_HELPER_EXPORT
56 #else // we are using shared lib/dll
57 #define TF_DECL ROS_HELPER_IMPORT
59 #else // ros is being built around static libraries
66 std::string
resolve(
const std::string& prefix,
const std::string& frame_name);
107 static const unsigned int MAX_GRAPH_DEPTH = 100UL;
109 static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL;
129 bool setTransform(
const StampedTransform& transform,
const std::string & authority =
"default_authority");
142 void lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
155 void lookupTransform(
const std::string& target_frame,
const ros::Time& target_time,
156 const std::string& source_frame,
const ros::Time& source_time,
179 void lookupTwist(
const std::string& tracking_frame,
const std::string& observation_frame,
const std::string& reference_frame,
180 const tf::Point & reference_point,
const std::string& reference_point_frame,
182 geometry_msgs::Twist& twist)
const;
194 void lookupTwist(
const std::string& tracking_frame,
const std::string& observation_frame,
196 geometry_msgs::Twist& twist)
const;
206 bool waitForTransform(
const std::string& target_frame,
const std::string& source_frame,
208 std::string* error_msg = NULL)
const;
215 bool canTransform(
const std::string& target_frame,
const std::string& source_frame,
217 std::string* error_msg = NULL)
const;
227 bool canTransform(
const std::string& target_frame,
const ros::Time& target_time,
228 const std::string& source_frame,
const ros::Time& source_time,
229 const std::string& fixed_frame,
230 std::string* error_msg = NULL)
const;
242 bool waitForTransform(
const std::string& target_frame,
const ros::Time& target_time,
243 const std::string& source_frame,
const ros::Time& source_time,
244 const std::string& fixed_frame,
246 std::string* error_msg = NULL)
const;
250 int getLatestCommonTime(
const std::string &source_frame,
const std::string &target_frame,
ros::Time& time, std::string* error_string)
const;
267 void transformQuaternion(
const std::string& target_frame,
const ros::Time& target_time,
269 const std::string& fixed_frame,
273 void transformVector(
const std::string& target_frame,
const ros::Time& target_time,
275 const std::string& fixed_frame,
279 void transformPoint(
const std::string& target_frame,
const ros::Time& target_time,
281 const std::string& fixed_frame,
285 void transformPose(
const std::string& target_frame,
const ros::Time& target_time,
287 const std::string& fixed_frame,
300 void chainAsVector(
const std::string & target_frame,
ros::Time target_time,
const std::string & source_frame,
ros::Time source_time,
const std::string & fixed_frame, std::vector<std::string>& output)
const;
305 std::string allFramesAsString()
const;
310 std::string allFramesAsDot(
double current_time = 0)
const;
313 void getFrameStrings(std::vector<std::string>& ids)
const;
319 bool getParent(
const std::string& frame_id,
ros::Time time, std::string& parent)
const;
323 bool frameExists(
const std::string& frame_id_str)
const;
340 boost::signals2::connection addTransformsChangedListener(boost::function<
void(
void)> callback);
341 void removeTransformsChangedListener(boost::signals2::connection c);
385 if (!fall_back_to_wall_time_)
395 virtual bool ok()
const;
411 if(std::isnan(q.x()) || std::isnan(q.y()) || std::isnan(q.z()) || std::isnan(q.w()))
413 std::stringstream ss;
414 ss <<
"Quaternion contains a NaN" << std::endl;
418 if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01)
420 std::stringstream ss;
421 ss <<
"Quaternion malformed, magnitude: " << q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() <<
" should be 1.0" <<std::endl;
429 if(std::isnan(q.x) || std::isnan(q.y) || std::isnan(q.z) || std::isnan(q.w))
431 std::stringstream ss;
432 ss <<
"Quaternion contains a NaN" << std::endl;
436 if(std::fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w - 1) > 0.01)
438 std::stringstream ss;
439 ss <<
"Quaternion malformed, magnitude: " << q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w <<
" should be 1.0" <<std::endl;