37 #ifndef MOVEIT_TRANSFORMS_ 38 #define MOVEIT_TRANSFORMS_ 40 #include <geometry_msgs/TransformStamped.h> 41 #include <Eigen/Geometry> 42 #include <boost/noncopyable.hpp> 53 typedef std::map<std::string, Eigen::Isometry3d, std::less<std::string>,
54 Eigen::aligned_allocator<std::pair<const std::string, Eigen::Isometry3d> > >
74 static bool sameFrame(
const std::string& frame1,
const std::string& frame2);
97 void copyTransforms(std::vector<geometry_msgs::TransformStamped>& transforms)
const;
104 void setTransform(
const Eigen::Isometry3d&
t,
const std::string& from_frame);
110 void setTransform(
const geometry_msgs::TransformStamped& transform);
116 void setTransforms(
const std::vector<geometry_msgs::TransformStamped>& transforms);
150 Eigen::Quaterniond& q_out)
const 172 void transformPose(
const std::string& from_frame,
const Eigen::Isometry3d& t_in, Eigen::Isometry3d& t_out)
const 181 virtual bool canTransform(
const std::string& from_frame)
const;
187 virtual bool isFixedFrame(
const std::string& frame)
const;
194 virtual const Eigen::Isometry3d&
getTransform(
const std::string& from_frame)
const;
Vec3fX< details::Vec3Data< double > > Vector3d
geometry_msgs::TransformStamped t
MOVEIT_CLASS_FORWARD(RobotModel)
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Main namespace for MoveIt!