37 #ifndef MOVEIT_TRANSFORMS_ 38 #define MOVEIT_TRANSFORMS_ 40 #include <geometry_msgs/TransformStamped.h> 41 #include <geometry_msgs/Pose.h> 42 #include <Eigen/Geometry> 43 #include <boost/noncopyable.hpp> 54 typedef std::map<std::string, Eigen::Affine3d, std::less<std::string>,
55 Eigen::aligned_allocator<std::pair<const std::string, Eigen::Affine3d> > >
75 static bool sameFrame(
const std::string& frame1,
const std::string& frame2);
98 void copyTransforms(std::vector<geometry_msgs::TransformStamped>& transforms)
const;
105 void setTransform(
const Eigen::Affine3d& t,
const std::string& from_frame);
111 void setTransform(
const geometry_msgs::TransformStamped& transform);
117 void setTransforms(
const std::vector<geometry_msgs::TransformStamped>& transforms);
139 void transformVector3(
const std::string& from_frame,
const Eigen::Vector3d& v_in, Eigen::Vector3d& v_out)
const 151 Eigen::Quaterniond& q_out)
const 173 void transformPose(
const std::string& from_frame,
const Eigen::Affine3d& t_in, Eigen::Affine3d& t_out)
const 182 virtual bool canTransform(
const std::string& from_frame)
const;
188 virtual bool isFixedFrame(
const std::string& frame)
const;
195 virtual const Eigen::Affine3d&
getTransform(
const std::string& from_frame)
const;
MOVEIT_CLASS_FORWARD(RobotModel)
Main namespace for MoveIt!
std::map< std::string, Eigen::Affine3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Affine3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...