38#include <geometric_shapes/check_isometry.h>
39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
41#include <tf2_eigen/tf2_eigen.hpp>
42#include <boost/algorithm/string/trim.hpp>
62 RCLCPP_ERROR(getLogger(),
"The target frame for MoveIt Transforms cannot be empty.");
72 if (frame1.empty() || frame2.empty())
74 return frame1 == frame2;
91 for (
const auto& t : transforms)
93 ASSERT_ISOMETRY(t.second)
112 if (!from_frame.empty())
114 FixedTransformsMap::const_iterator it =
transforms_map_.find(from_frame);
120 RCLCPP_ERROR(getLogger(),
"Unable to transform from frame '%s' to frame '%s'. Returning identity.",
124 static const Eigen::Isometry3d IDENTITY = Eigen::Isometry3d::Identity();
130 if (from_frame.empty())
143 if (from_frame.empty())
145 RCLCPP_ERROR(getLogger(),
"Cannot record transform with empty name");
157 const auto& trans = transform.transform.translation;
158 const auto& rot = transform.transform.rotation;
159 Eigen::Translation3d translation(trans.x, trans.y, trans.z);
160 Eigen::Quaterniond rotation(rot.w, rot.x, rot.y, rot.z);
161 rotation.normalize();
163 setTransform(translation * rotation, transform.header.frame_id);
167 RCLCPP_ERROR(getLogger(),
"Given transform is to frame '%s', but frame '%s' was expected.",
174 for (
const geometry_msgs::msg::TransformStamped& transform : transforms)
184 transforms[i] = tf2::eigenToTransform(it->second);
186 transforms[i].header.frame_id = it->first;
rclcpp::Logger getLogger()
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.