45 #include <boost/unordered_map.hpp> 46 #include <boost/signals2.hpp> 47 #include "geometry_msgs/TwistStamped.h" 54 #if defined(_WIN32) && defined(NO_ERROR) 59 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries 60 #ifdef tf_EXPORTS // we are building a shared lib/dll 61 #define TF_DECL ROS_HELPER_EXPORT 62 #else // we are using shared lib/dll 63 #define TF_DECL ROS_HELPER_IMPORT 65 #else // ros is being built around static libraries 72 std::string
resolve(
const std::string& prefix,
const std::string& frame_name);
113 static const unsigned int MAX_GRAPH_DEPTH = 100UL;
115 static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL;
135 bool setTransform(
const StampedTransform& transform,
const std::string & authority =
"default_authority");
148 void lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
161 void lookupTransform(
const std::string& target_frame,
const ros::Time& target_time,
162 const std::string& source_frame,
const ros::Time& source_time,
185 void lookupTwist(
const std::string& tracking_frame,
const std::string& observation_frame,
const std::string& reference_frame,
186 const tf::Point & reference_point,
const std::string& reference_point_frame,
188 geometry_msgs::Twist& twist)
const;
200 void lookupTwist(
const std::string& tracking_frame,
const std::string& observation_frame,
202 geometry_msgs::Twist& twist)
const;
212 bool waitForTransform(
const std::string& target_frame,
const std::string& source_frame,
214 std::string* error_msg = NULL)
const;
221 bool canTransform(
const std::string& target_frame,
const std::string& source_frame,
223 std::string* error_msg = NULL)
const;
233 bool canTransform(
const std::string& target_frame,
const ros::Time& target_time,
234 const std::string& source_frame,
const ros::Time& source_time,
235 const std::string& fixed_frame,
236 std::string* error_msg = NULL)
const;
248 bool waitForTransform(
const std::string& target_frame,
const ros::Time& target_time,
249 const std::string& source_frame,
const ros::Time& source_time,
250 const std::string& fixed_frame,
252 std::string* error_msg = NULL)
const;
256 int getLatestCommonTime(
const std::string &source_frame,
const std::string &target_frame,
ros::Time& time, std::string* error_string)
const;
273 void transformQuaternion(
const std::string& target_frame,
const ros::Time& target_time,
275 const std::string& fixed_frame,
279 void transformVector(
const std::string& target_frame,
const ros::Time& target_time,
281 const std::string& fixed_frame,
285 void transformPoint(
const std::string& target_frame,
const ros::Time& target_time,
287 const std::string& fixed_frame,
291 void transformPose(
const std::string& target_frame,
const ros::Time& target_time,
293 const std::string& fixed_frame,
306 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;
311 std::string allFramesAsString()
const;
316 std::string allFramesAsDot(
double current_time = 0)
const;
319 void getFrameStrings(std::vector<std::string>& ids)
const;
325 bool getParent(
const std::string& frame_id,
ros::Time time, std::string& parent)
const;
329 bool frameExists(
const std::string& frame_id_str)
const;
346 boost::signals2::connection addTransformsChangedListener(boost::function<
void(
void)> callback);
347 void removeTransformsChangedListener(boost::signals2::connection c);
360 std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr() {
return tf2_buffer_ptr_;};
391 if (!fall_back_to_wall_time_)
401 virtual bool ok()
const;
417 if(std::isnan(q.x()) || std::isnan(q.y()) || std::isnan(q.z()) || std::isnan(q.w()))
419 std::stringstream ss;
420 ss <<
"Quaternion contains a NaN" << std::endl;
424 if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01)
426 std::stringstream ss;
427 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;
435 if(std::isnan(q.x) || std::isnan(q.y) || std::isnan(q.z) || std::isnan(q.w))
437 std::stringstream ss;
438 ss <<
"Quaternion contains a NaN" << std::endl;
442 if(std::fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w - 1) > 0.01)
444 std::stringstream ss;
445 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;
void assertQuaternionValid(const tf::Quaternion &q)
Throw InvalidArgument if quaternion is malformed.
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
static ROS_DEPRECATED std::string remap(const std::string &prefix, const std::string &frame_name)
std::string resolve(const std::string &prefix, const std::string &frame_name)
resolve tf names
The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of...
tf2::InvalidArgumentException InvalidArgument
std::string strip_leading_slash(const std::string &frame_name)