Robowflex  v0.1
Making MoveIt Easy
tf.h File Reference
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/TransformStamped.h>
#include <moveit_msgs/BoundingVolume.h>
#include <moveit_msgs/PositionConstraint.h>
#include <moveit_msgs/OrientationConstraint.h>
#include <robowflex_library/class_forward.h>
#include <robowflex_library/adapter.h>
#include <robowflex_library/constants.h>

Go to the source code of this file.

Namespaces

 robowflex
 Main namespace. Contains all library classes and functions.
 
 robowflex::TF
 Collection of methods relating to transforms and transform math.
 

Functions

RobotPose robowflex::TF::identity ()
 Creates the Identity pose. More...
 
RobotPose robowflex::TF::createPoseXYZ (double x, double y, double z)
 Creates a robot pose from a linear component and zero orientation. More...
 
RobotPose robowflex::TF::createPoseXYZ (const Eigen::Ref< const Eigen::Vector3d > &translation)
 Creates a robot pose from a linear component and zero orientation. More...
 
RobotPose robowflex::TF::createPoseXYZ (double x, double y, double z, double X, double Y, double Z)
 Creates a robot pose from a linear component and XYZ convention Euler angles. More...
 
RobotPose robowflex::TF::createPoseXYZ (const Eigen::Ref< const Eigen::Vector3d > &translation, const Eigen::Ref< const Eigen::Vector3d > &rotation)
 Creates a robot pose from a linear component and XYZ convention Euler angles. More...
 
RobotPose robowflex::TF::createPoseQ (double x, double y, double z, double W, double X, double Y, double Z)
 Creates a robot pose from a linear component and a Quaternion. More...
 
RobotPose robowflex::TF::createPoseQ (const Eigen::Ref< const Eigen::Vector3d > &translation, const Eigen::Ref< const Eigen::Vector4d > &rotation)
 Creates a robot pose from a linear component and a quaternion. More...
 
RobotPose robowflex::TF::createPoseQ (const Eigen::Ref< const Eigen::Vector3d > &translation, const Eigen::Quaterniond &rotation)
 Creates a robot pose from a linear component and a quaternion. More...
 
Eigen::Quaterniond robowflex::TF::getPoseRotation (const RobotPose &pose)
 Get the rotational component of a robot pose. More...
 
Eigen::Vector3d robowflex::TF::pointMsgToEigen (const geometry_msgs::Point &msg)
 Converts a point message to an Eigen::Vector3d. More...
 
geometry_msgs::Point robowflex::TF::pointEigenToMsg (const Eigen::Vector3d &vector)
 Converts an Eigen::Vector3d to a point message. More...
 
Eigen::Vector3d robowflex::TF::vectorMsgToEigen (const geometry_msgs::Vector3 &msg)
 Converts a vector message to an Eigen::Vector3d. More...
 
geometry_msgs::Vector3 robowflex::TF::vectorEigenToMsg (const Eigen::Vector3d &vector)
 Converts an Eigen::Vector3d to a vector message. More...
 
RobotPose robowflex::TF::poseMsgToEigen (const geometry_msgs::Pose &msg)
 Converts a pose message to RobotPose. More...
 
geometry_msgs::Pose robowflex::TF::poseEigenToMsg (const RobotPose &pose)
 Converts an RobotPose to a pose message. More...
 
Eigen::Quaterniond robowflex::TF::quaternionMsgToEigen (const geometry_msgs::Quaternion &msg)
 Converts a quaternion message to Eigen::Quaterniond. More...
 
geometry_msgs::Quaternion robowflex::TF::quaternionEigenToMsg (const Eigen::Quaterniond &quaternion)
 Converts an Eigen::Quaterniond to a quaternion message. More...
 
moveit_msgs::BoundingVolume robowflex::TF::getBoundingVolume (const RobotPose &pose, const GeometryConstPtr &geometry)
 Get a bounding volume message for given geometry at a pose. More...
 
moveit_msgs::PositionConstraint robowflex::TF::getPositionConstraint (const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry)
 Get a position constraint message. More...
 
Eigen::Vector3d robowflex::TF::samplePositionConstraint (const moveit_msgs::PositionConstraint &pc)
 
moveit_msgs::OrientationConstraint robowflex::TF::getOrientationConstraint (const std::string &ee_name, const std::string &base_name, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
 Get an orientation constraint message. More...
 
Eigen::Quaterniond robowflex::TF::sampleOrientation (const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
 Sample an orientation from a given orientation with XYZ Euler angle tolerances. More...
 
Eigen::Quaterniond robowflex::TF::sampleOrientationUniform (const Eigen::Vector3d &tolerances)
 Sample an orientation within the XYZ Euler angle tolerances. More...
 
Eigen::Quaterniond robowflex::TF::offsetOrientation (const Eigen::Quaterniond &orientation, const Eigen::Vector3d &axis, double value)
 Offset an orientation by a rotation about an axis. More...
 
Eigen::Vector3d robowflex::TF::samplePositionUniform (const Eigen::Vector3d &bounds)
 Sample a position within the given bounds using a uniform distribution. More...
 
Eigen::Vector3d robowflex::TF::samplePositionGaussian (const Eigen::Vector3d &stddev)
 Sample a position from a gaussian distribution with mean zero and given standard deviation. More...
 
RobotPose robowflex::TF::samplePoseUniform (const Eigen::Vector3d &pos_bounds, const Eigen::Vector3d &orn_bounds)
 Sample a pose within the given position, orientation bounds. More...
 
RobotPose robowflex::TF::samplePoseGaussian (const Eigen::Vector3d &pos_stddev, const Eigen::Vector3d &orn_bounds)
 Sample a pose with gaussian sampling for the position with given standard deviations and uniform sampling for the orientation within the given bounds. More...
 
RobotPose robowflex::TF::transformMsgToEigen (const geometry_msgs::TransformStamped &tf)
 Decode a message as a transform. More...
 
geometry_msgs::TransformStamped robowflex::TF::transformEigenToMsg (const std::string &source, const std::string &target, const RobotPose &tf)
 Encode a transform as a message. More...
 
double robowflex::TF::angleNormalize (double v)
 Normalize an angle between -pi to pi. More...
 
double robowflex::TF::toDegrees (double v)
 Convert an angle to degrees. More...
 
double robowflex::TF::toRadians (double v)
 Convert an angle to radians. More...
 
bool robowflex::TF::isVecZero (const Eigen::Ref< const Eigen::VectorXd > &v, double tolerance=constants::eps)
 Checks if a vector is close to zero. More...