This class inherits from Transformer and automatically subscribes to ROS transform messages. More...
#include <transform_listener.h>
Public Member Functions | |
bool | getFrames (tf::FrameGraph::Request &, tf::FrameGraph::Response &res) |
std::string | resolve (const std::string &frame_name) |
TransformListener (ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true) | |
Constructor for transform listener. | |
TransformListener (const ros::NodeHandle &nh, ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true) | |
Alternate constructor for transform listener. | |
void | transformPoint (const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const |
Transform a Stamped Point Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformPoint (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::PointStamped &pin, const std::string &fixed_frame, geometry_msgs::PointStamped &pout) const |
Transform a Stamped Point Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformPointCloud (const std::string &target_frame, const sensor_msgs::PointCloud &pcin, sensor_msgs::PointCloud &pcout) const |
Transform a sensor_msgs::PointCloud natively This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformPointCloud (const std::string &target_frame, const ros::Time &target_time, const sensor_msgs::PointCloud &pcin, const std::string &fixed_frame, sensor_msgs::PointCloud &pcout) const |
Transform a sensor_msgs::PointCloud in space and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformPose (const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const |
Transform a Stamped Pose Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformPose (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::PoseStamped &pin, const std::string &fixed_frame, geometry_msgs::PoseStamped &pout) const |
Transform a Stamped Pose Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformQuaternion (const std::string &target_frame, const geometry_msgs::QuaternionStamped &stamped_in, geometry_msgs::QuaternionStamped &stamped_out) const |
Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformQuaternion (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::QuaternionStamped &qin, const std::string &fixed_frame, geometry_msgs::QuaternionStamped &qout) const |
Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformVector (const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const |
Transform a Stamped Vector Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
void | transformVector (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::Vector3Stamped &vin, const std::string &fixed_frame, geometry_msgs::Vector3Stamped &vout) const |
Transform a Stamped Vector Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. | |
~TransformListener () | |
Protected Member Functions | |
bool | ok () const |
Private Member Functions | |
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 |
a helper function to be used for both transfrom pointCloud methods | |
Private Attributes | |
ros::NodeHandle | node_ |
tf2_ros::TransformListener | tf2_listener_ |
replacing implementation with tf2_ros' |
This class inherits from Transformer and automatically subscribes to ROS transform messages.
Definition at line 69 of file transform_listener.h.
TransformListener::TransformListener | ( | ros::Duration | max_cache_time = ros::Duration(DEFAULT_CACHE_TIME) , |
bool | spin_thread = true |
||
) |
Constructor for transform listener.
max_cache_time | How long to store transform information |
Definition at line 43 of file transform_listener.cpp.
TransformListener::TransformListener | ( | const ros::NodeHandle & | nh, |
ros::Duration | max_cache_time = ros::Duration(DEFAULT_CACHE_TIME) , |
||
bool | spin_thread = true |
||
) |
Alternate constructor for transform listener.
nh | The NodeHandle to use for any ROS interaction |
max_cache_time | How long to store transform information |
Definition at line 49 of file transform_listener.cpp.
Definition at line 55 of file transform_listener.cpp.
bool tf::TransformListener::getFrames | ( | tf::FrameGraph::Request & | , |
tf::FrameGraph::Response & | res | ||
) | [inline] |
Definition at line 147 of file transform_listener.h.
bool TransformListener::ok | ( | ) | const [protected, virtual] |
Reimplemented from tf::Transformer.
Definition at line 61 of file transform_listener.cpp.
std::string tf::TransformListener::resolve | ( | const std::string & | frame_name | ) | [inline] |
Definition at line 154 of file transform_listener.h.
void TransformListener::transformPoint | ( | const std::string & | target_frame, |
const geometry_msgs::PointStamped & | stamped_in, | ||
geometry_msgs::PointStamped & | stamped_out | ||
) | const |
Transform a Stamped Point Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 87 of file transform_listener.cpp.
void TransformListener::transformPoint | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
const geometry_msgs::PointStamped & | pin, | ||
const std::string & | fixed_frame, | ||
geometry_msgs::PointStamped & | pout | ||
) | const |
Transform a Stamped Point Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 162 of file transform_listener.cpp.
void TransformListener::transformPointCloud | ( | const std::string & | target_frame, |
const sensor_msgs::PointCloud & | pcin, | ||
sensor_msgs::PointCloud & | pcout | ||
) | const |
Transform a sensor_msgs::PointCloud natively This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 184 of file transform_listener.cpp.
void TransformListener::transformPointCloud | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
const sensor_msgs::PointCloud & | pcin, | ||
const std::string & | fixed_frame, | ||
sensor_msgs::PointCloud & | pcout | ||
) | const |
Transform a sensor_msgs::PointCloud in space and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 191 of file transform_listener.cpp.
void TransformListener::transformPointCloud | ( | const std::string & | target_frame, |
const Transform & | transform, | ||
const ros::Time & | target_time, | ||
const sensor_msgs::PointCloud & | pcin, | ||
sensor_msgs::PointCloud & | pcout | ||
) | const [private] |
a helper function to be used for both transfrom pointCloud methods
Definition at line 217 of file transform_listener.cpp.
void TransformListener::transformPose | ( | const std::string & | target_frame, |
const geometry_msgs::PoseStamped & | stamped_in, | ||
geometry_msgs::PoseStamped & | stamped_out | ||
) | const |
Transform a Stamped Pose Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 97 of file transform_listener.cpp.
void TransformListener::transformPose | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
const geometry_msgs::PoseStamped & | pin, | ||
const std::string & | fixed_frame, | ||
geometry_msgs::PoseStamped & | pout | ||
) | const |
Transform a Stamped Pose Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 172 of file transform_listener.cpp.
void TransformListener::transformQuaternion | ( | const std::string & | target_frame, |
const geometry_msgs::QuaternionStamped & | stamped_in, | ||
geometry_msgs::QuaternionStamped & | stamped_out | ||
) | const |
Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 65 of file transform_listener.cpp.
void TransformListener::transformQuaternion | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
const geometry_msgs::QuaternionStamped & | qin, | ||
const std::string & | fixed_frame, | ||
geometry_msgs::QuaternionStamped & | qout | ||
) | const |
Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 141 of file transform_listener.cpp.
void TransformListener::transformVector | ( | const std::string & | target_frame, |
const geometry_msgs::Vector3Stamped & | stamped_in, | ||
geometry_msgs::Vector3Stamped & | stamped_out | ||
) | const |
Transform a Stamped Vector Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 77 of file transform_listener.cpp.
void TransformListener::transformVector | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
const geometry_msgs::Vector3Stamped & | vin, | ||
const std::string & | fixed_frame, | ||
geometry_msgs::Vector3Stamped & | vout | ||
) | const |
Transform a Stamped Vector Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
Definition at line 152 of file transform_listener.cpp.
ros::NodeHandle tf::TransformListener::node_ [private] |
Definition at line 167 of file transform_listener.h.
replacing implementation with tf2_ros'
Definition at line 170 of file transform_listener.h.