#include <tf_manager.hpp>

Public Member Functions | |
| bool | getPoseInFrame (const std::string &frame, const geometry_msgs::PoseStamped &pose, geometry_msgs::PoseStamped &out) |
| TFManager (ros::NodeHandle nh=ros::NodeHandle("~")) | |
| ~TFManager () | |
Public Member Functions inherited from generic_control_toolbox::ManagerBase | |
| ManagerBase () | |
| virtual | ~ManagerBase () |
Private Member Functions | |
| bool | getParam () |
Private Attributes | |
| tf::TransformListener | listener_ |
| int | max_tf_attempts_ |
| ros::NodeHandle | nh_ |
Provides helper methods to handle common TF queries.
Definition at line 14 of file tf_manager.hpp.
| generic_control_toolbox::TFManager::TFManager | ( | ros::NodeHandle | nh = ros::NodeHandle("~") | ) |
Definition at line 5 of file tf_manager.cpp.
|
inline |
Definition at line 18 of file tf_manager.hpp.
|
private |
Definition at line 46 of file tf_manager.cpp.
| bool generic_control_toolbox::TFManager::getPoseInFrame | ( | const std::string & | frame, |
| const geometry_msgs::PoseStamped & | pose, | ||
| geometry_msgs::PoseStamped & | out | ||
| ) |
Convert a pose to another frame using the TF tree. Handles TF exceptions.
| frame | The target frame to which to transform the given pose. |
| pose | The given pose. queried, after which a failure is assumed. |
| out | The given pose in the given frame. |
Definition at line 13 of file tf_manager.cpp.
|
private |
Definition at line 38 of file tf_manager.hpp.
|
private |
Definition at line 37 of file tf_manager.hpp.
|
private |
Definition at line 36 of file tf_manager.hpp.