40 #include <boost/algorithm/string/trim.hpp>
49 boost::trim(target_frame_);
50 if (target_frame_.empty())
51 ROS_ERROR_NAMED(
"transforms",
"The target frame for MoveIt Transforms cannot be empty.");
54 transforms_map_[target_frame_] = Eigen::Isometry3d::Identity();
58 bool Transforms::sameFrame(
const std::string& frame1,
const std::string& frame2)
60 if (frame1.empty() || frame2.empty())
62 return frame1 == frame2;
65 Transforms::~Transforms() =
default;
67 const std::string& Transforms::getTargetFrame()
const
74 return transforms_map_;
79 for (
const auto& t : transforms)
83 transforms_map_ = transforms;
86 bool Transforms::isFixedFrame(
const std::string& frame)
const
91 return transforms_map_.find(frame) != transforms_map_.end();
94 const Eigen::Isometry3d& Transforms::getTransform(
const std::string& from_frame)
const
96 if (!from_frame.empty())
98 FixedTransformsMap::const_iterator it = transforms_map_.find(from_frame);
99 if (it != transforms_map_.end())
104 ROS_ERROR_NAMED(
"transforms",
"Unable to transform from frame '%s' to frame '%s'. Returning identity.",
105 from_frame.c_str(), target_frame_.c_str());
108 static const Eigen::Isometry3d IDENTITY = Eigen::Isometry3d::Identity();
112 bool Transforms::canTransform(
const std::string& from_frame)
const
114 if (from_frame.empty())
117 return transforms_map_.find(from_frame) != transforms_map_.end();
120 void Transforms::setTransform(
const Eigen::Isometry3d& t,
const std::string& from_frame)
123 if (from_frame.empty())
124 ROS_ERROR_NAMED(
"transforms",
"Cannot record transform with empty name");
126 transforms_map_[from_frame] =
t;
129 void Transforms::setTransform(
const geometry_msgs::TransformStamped& transform)
135 const auto& trans =
transform.transform.translation;
137 Eigen::Translation3d translation(trans.x, trans.y, trans.z);
138 Eigen::Quaterniond rotation(rot.w, rot.x, rot.y, rot.z);
139 rotation.normalize();
141 setTransform(translation * rotation,
transform.header.frame_id);
145 ROS_ERROR_NAMED(
"transforms",
"Given transform is to frame '%s', but frame '%s' was expected.",
146 transform.child_frame_id.c_str(), target_frame_.c_str());
150 void Transforms::setTransforms(
const std::vector<geometry_msgs::TransformStamped>& transforms)
152 for (
const geometry_msgs::TransformStamped&
transform : transforms)
156 void Transforms::copyTransforms(std::vector<geometry_msgs::TransformStamped>& transforms)
const
158 transforms.resize(transforms_map_.size());
160 for (FixedTransformsMap::const_iterator it = transforms_map_.begin(); it != transforms_map_.end(); ++it, ++i)
163 transforms[i].child_frame_id = target_frame_;
164 transforms[i].header.frame_id = it->first;