#include <transformer.h>
Public Member Functions | |
Transformer () | |
virtual | ~Transformer () |
Static Public Member Functions | |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::Point &point) |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::Quaternion &quaternion) |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::Pose &pose) |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::PointStamped &point) |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::QuaternionStamped &quaternion) |
static bool | transform (const std::string &new_frame, const std::string &old_frame, const arm_navigation_msgs::RobotState &robotState, geometry_msgs::PoseStamped &pose) |
static bool | transform (const std::string &new_frame, const arm_navigation_msgs::RobotState &robotState, arm_navigation_msgs::Constraints &constraint) |
Private Member Functions | |
bool | getTransform (const std::string &to_frame, const std::string &from_frame, const arm_navigation_msgs::RobotState &robotState, tf::Transform &transform) |
bool | getWorldTransform (const std::string &frame_id, const planning_models::KinematicState &state, tf::Transform &transform) |
std::string | relative_frame (const std::string &frame_id) const |
Private Attributes | |
planning_environment::RobotModels | robot_model |
Static Private Attributes | |
static Transformer * | instance = NULL |
Definition at line 23 of file transformer.h.
Definition at line 12 of file transformer.cpp.
Transformer::~Transformer | ( | void | ) | [virtual] |
Definition at line 17 of file transformer.cpp.
bool Transformer::getTransform | ( | const std::string & | to_frame, |
const std::string & | from_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
tf::Transform & | transform | ||
) | [private] |
Definition at line 30 of file transformer.cpp.
bool Transformer::getWorldTransform | ( | const std::string & | frame_id, |
const planning_models::KinematicState & | state, | ||
tf::Transform & | transform | ||
) | [private] |
Definition at line 70 of file transformer.cpp.
std::string Transformer::relative_frame | ( | const std::string & | frame_id | ) | const [private] |
Definition at line 21 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::Point & | point | ||
) | [static] |
Definition at line 98 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::Quaternion & | quaternion | ||
) | [static] |
Definition at line 118 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::Pose & | pose | ||
) | [static] |
Definition at line 139 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::PointStamped & | point | ||
) | [static] |
Definition at line 167 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::QuaternionStamped & | quaternion | ||
) | [static] |
Definition at line 180 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const std::string & | old_frame, | ||
const arm_navigation_msgs::RobotState & | robotState, | ||
geometry_msgs::PoseStamped & | pose | ||
) | [static] |
Definition at line 193 of file transformer.cpp.
bool Transformer::transform | ( | const std::string & | new_frame, |
const arm_navigation_msgs::RobotState & | robotState, | ||
arm_navigation_msgs::Constraints & | constraint | ||
) | [static] |
Definition at line 206 of file transformer.cpp.
Transformer * Transformer::instance = NULL [static, private] |
Definition at line 60 of file transformer.h.
Definition at line 69 of file transformer.h.