Go to the documentation of this file.
32 #ifndef TF_TRANSFORMLISTENER_H
33 #define TF_TRANSFORMLISTENER_H
35 #include "sensor_msgs/PointCloud.h"
36 #include "std_msgs/Empty.h"
37 #include "tf/tfMessage.h"
43 #include "tf/FrameGraph.h"
44 #include "boost/thread.hpp"
60 std::string return_val;
96 void transformQuaternion(
const std::string& target_frame,
const geometry_msgs::QuaternionStamped& stamped_in, geometry_msgs::QuaternionStamped& stamped_out)
const;
99 void transformVector(
const std::string& target_frame,
const geometry_msgs::Vector3Stamped& stamped_in, geometry_msgs::Vector3Stamped& stamped_out)
const;
102 void transformPoint(
const std::string& target_frame,
const geometry_msgs::PointStamped& stamped_in, geometry_msgs::PointStamped& stamped_out)
const;
105 void transformPose(
const std::string& target_frame,
const geometry_msgs::PoseStamped& stamped_in, geometry_msgs::PoseStamped& stamped_out)
const;
115 const geometry_msgs::QuaternionStamped& qin,
116 const std::string& fixed_frame, geometry_msgs::QuaternionStamped& qout)
const;
120 const geometry_msgs::Vector3Stamped& vin,
121 const std::string& fixed_frame, geometry_msgs::Vector3Stamped& vout)
const;
125 const geometry_msgs::PointStamped& pin,
126 const std::string& fixed_frame, geometry_msgs::PointStamped& pout)
const;
130 const geometry_msgs::PoseStamped& pin,
131 const std::string& fixed_frame, geometry_msgs::PoseStamped& pout)
const;
136 void transformPointCloud(
const std::string& target_frame,
const sensor_msgs::PointCloud& pcin, sensor_msgs::PointCloud& pcout)
const;
141 const sensor_msgs::PointCloud& pcin,
142 const std::string& fixed_frame, sensor_msgs::PointCloud& pcout)
const;
148 bool getFrames(tf::FrameGraph::Request&, tf::FrameGraph::Response& res)
155 std::string
resolve(
const std::string& frame_name)
174 void transformPointCloud(
const std::string & target_frame,
const Transform& transform,
const ros::Time& target_time,
const sensor_msgs::PointCloud& pcin, sensor_msgs::PointCloud& pcout)
const;
179 #endif //TF_TRANSFORMLISTENER_H
bool getParam(const std::string &key, bool &b) const
std::string resolve(const std::string &prefix, const std::string &frame_name)
resolve tf names
std::string getPrefixParam(ros::NodeHandle &nh)
Get the tf_prefix from the parameter server.
bool searchParam(const std::string &key, std::string &result) const
T param(const std::string ¶m_name, const T &default_val)
static ROS_DEPRECATED std::string remap(const std::string &prefix, const std::string &frame_name)
tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Wed Mar 2 2022 00:20:05