Class cartesian_utils
Defined in File cartesian_utils.h
Class Documentation
- 
class cartesian_utils
 Public Static Functions
- 
static void computePanTiltMatrix(const Eigen::VectorXd &gaze, KDL::Frame &pan_tilt_matrix)
 computePanTiltMatrix given a gaze vector computes the Homogeneous Matrix to control the YAW-PITCH angles.
The algorithm used is based on the paper: “Adaptive Predictive Gaze Control of a Redundant Humanoid
Robot Head, IROS2011”.
- Parameters
 gaze – vector [3x1]
pan_tilt_matrix – Homogeneous Matrix [4x4] in the same reference frame of the gaze vector
- 
static void computeCartesianError(const Eigen::Matrix4d &T, const Eigen::Matrix4d &Td, Eigen::Vector3d &position_error, Eigen::Vector3d &orientation_error)
 computeCartesianError orientation and position error
- Parameters
 T – actual pose Homogeneous Matrix [4x4]
Td – desired pose Homogeneous Matrix [4x4]
position_error – position error [3x1]
orientation_error – orientation error [3x1]
- 
static void computeCartesianError(const Eigen::Affine3d &T, const Eigen::Affine3d &Td, Eigen::Vector3d &position_error, Eigen::Vector3d &orientation_error)
 computeCartesianError orientation and position error
- Parameters
 T – actual pose
Td – desired pose
position_error – position error
orientation_error – orientation error
- 
static void computePanTiltMatrix(const Eigen::VectorXd &gaze, KDL::Frame &pan_tilt_matrix)