Functions | |
void | robot_state::Transforms::transformPose (const std::string &from_frame, const Eigen::Affine3d &t_in, Eigen::Affine3d &t_out) const |
Transform a pose in from_frame to the target_frame. | |
void | robot_state::Transforms::transformQuaternion (const std::string &from_frame, const Eigen::Quaterniond &q_in, Eigen::Quaterniond &q_out) const |
Transform a quaternion in from_frame to the target_frame. | |
void | robot_state::Transforms::transformRotationMatrix (const std::string &from_frame, const Eigen::Matrix3d &m_in, Eigen::Matrix3d &m_out) const |
Transform a rotation matrix in from_frame to the target_frame. | |
void | robot_state::Transforms::transformVector3 (const std::string &from_frame, const Eigen::Vector3d &v_in, Eigen::Vector3d &v_out) const |
Transform a vector in from_frame to the target_frame. |
void robot_state::Transforms::transformPose | ( | const std::string & | from_frame, |
const Eigen::Affine3d & | t_in, | ||
Eigen::Affine3d & | t_out | ||
) | const [inline] |
Transform a pose in from_frame to the target_frame.
from_frame | The frame in which the input pose is specified |
t_in | The input pose (in from_frame) |
t_out | The resultant (transformed) pose |
Definition at line 168 of file transforms.h.
void robot_state::Transforms::transformQuaternion | ( | const std::string & | from_frame, |
const Eigen::Quaterniond & | q_in, | ||
Eigen::Quaterniond & | q_out | ||
) | const [inline] |
Transform a quaternion in from_frame to the target_frame.
from_frame | The frame in which the input quaternion is specified |
v_in | The input quaternion (in from_frame) |
v_out | The resultant (transformed) quaternion |
Definition at line 146 of file transforms.h.
void robot_state::Transforms::transformRotationMatrix | ( | const std::string & | from_frame, |
const Eigen::Matrix3d & | m_in, | ||
Eigen::Matrix3d & | m_out | ||
) | const [inline] |
Transform a rotation matrix in from_frame to the target_frame.
from_frame | The frame in which the input rotation matrix is specified |
m_in | The input rotation matrix (in from_frame) |
m_out | The resultant (transformed) rotation matrix |
Definition at line 157 of file transforms.h.
void robot_state::Transforms::transformVector3 | ( | const std::string & | from_frame, |
const Eigen::Vector3d & | v_in, | ||
Eigen::Vector3d & | v_out | ||
) | const [inline] |
Transform a vector in from_frame to the target_frame.
from_frame | The frame from which the transform is computed |
v_in | The input vector (in from_frame) |
v_out | The resultant (transformed) vector |
Definition at line 135 of file transforms.h.