39 #include <boost/algorithm/string/trim.hpp> 50 ROS_ERROR_NAMED(
"transforms",
"The target frame for MoveIt! Transforms cannot be empty.");
56 "Frame '%s' specified as target frame for MoveIt! Transforms. Assuming '/%s' instead.",
66 if (frame1.empty() || frame2.empty())
72 return frame1 == frame2;
102 if (!from_frame.empty())
104 FixedTransformsMap::const_iterator it =
110 ROS_ERROR_NAMED(
"transforms",
"Unable to transform from frame '%s' to frame '%s'. Returning identity.",
114 static const Eigen::Affine3d identity = Eigen::Affine3d::Identity();
120 if (from_frame.empty())
129 if (from_frame.empty())
130 ROS_ERROR_NAMED(
"transforms",
"Cannot record transform with empty name");
133 if (from_frame[0] !=
'/')
135 ROS_WARN_NAMED(
"transforms",
"Transform specified for frame '%s'. Assuming '/%s' instead", from_frame.c_str(),
154 ROS_ERROR_NAMED(
"transforms",
"Given transform is to frame '%s', but frame '%s' was expected.",
161 for (std::size_t i = 0; i < transforms.size(); ++i)
172 transforms[i].header.frame_id = it->first;
#define ROS_WARN_NAMED(name,...)
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
#define ROS_ERROR_NAMED(name,...)
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...