39 #include <geometry_msgs/msg/transform_stamped.hpp>
40 #include <Eigen/Geometry>
53 Eigen::aligned_allocator<std::pair<const std::string, Eigen::Isometry3d> > >;
82 static bool sameFrame(
const std::string& frame1,
const std::string& frame2);
106 void copyTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms)
const;
113 void setTransform(
const Eigen::Isometry3d& t,
const std::string& from_frame);
119 void setTransform(
const geometry_msgs::msg::TransformStamped& transform);
125 void setTransforms(
const std::vector<geometry_msgs::msg::TransformStamped>& transforms);
160 Eigen::Quaterniond& q_out)
const
184 void transformPose(
const std::string& from_frame,
const Eigen::Isometry3d& t_in, Eigen::Isometry3d& t_out)
const
194 virtual bool canTransform(
const std::string& from_frame)
const;
200 virtual bool isFixedFrame(
const std::string& frame)
const;
207 virtual const Eigen::Isometry3d&
getTransform(
const std::string& from_frame)
const;
Vec3fX< details::Vec3Data< double > > Vector3d
MOVEIT_CLASS_FORWARD(JointModelGroup)
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.