Go to the documentation of this file.
   39 #include <geometry_msgs/TransformStamped.h> 
   40 #include <Eigen/Geometry> 
   41 #include <boost/noncopyable.hpp> 
   52 using FixedTransformsMap = std::map<std::string, Eigen::Isometry3d, std::less<std::string>,
 
   53                                     Eigen::aligned_allocator<std::pair<const std::string, Eigen::Isometry3d> > >;
 
   58 class Transforms : 
private boost::noncopyable
 
   72   static bool sameFrame(
const std::string& frame1, 
const std::string& frame2);
 
   96   void copyTransforms(std::vector<geometry_msgs::TransformStamped>& transforms) 
const;
 
  103   void setTransform(
const Eigen::Isometry3d& t, 
const std::string& from_frame);
 
  109   void setTransform(
const geometry_msgs::TransformStamped& transform);
 
  115   void setTransforms(
const std::vector<geometry_msgs::TransformStamped>& transforms);
 
  150                            Eigen::Quaterniond& q_out)
 const 
  162   void transformRotationMatrix(
const std::string& from_frame, 
const Eigen::Matrix3d& m_in, Eigen::Matrix3d& m_out)
 const 
  174   void transformPose(
const std::string& from_frame, 
const Eigen::Isometry3d& t_in, Eigen::Isometry3d& t_out)
 const 
  184   virtual bool canTransform(
const std::string& from_frame) 
const;
 
  190   virtual bool isFixedFrame(
const std::string& frame) 
const;
 
  197   virtual const Eigen::Isometry3d& 
getTransform(
const std::string& from_frame) 
const;
 
  
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.
MOVEIT_CLASS_FORWARD(JointModelGroup)
Vec3fX< details::Vec3Data< double > > Vector3d
moveit_core
Author(s): Ioan Sucan 
, Sachin Chitta , Acorn Pooley 
autogenerated on Sat May 3 2025 02:25:32