moveit2
The MoveIt Motion Planning Framework for ROS 2.
transforms.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
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>
43 
44 namespace moveit
45 {
46 namespace core
47 {
48 // Logger
49 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_transforms.transforms");
50 
51 Transforms::Transforms(const std::string& target_frame) : target_frame_(target_frame)
52 {
53  boost::trim(target_frame_);
54  if (target_frame_.empty())
55  {
56  RCLCPP_ERROR(LOGGER, "The target frame for MoveIt Transforms cannot be empty.");
57  }
58  else
59  {
60  transforms_map_[target_frame_] = Eigen::Isometry3d::Identity();
61  }
62 }
63 
64 bool Transforms::sameFrame(const std::string& frame1, const std::string& frame2)
65 {
66  if (frame1.empty() || frame2.empty())
67  return false;
68  return frame1 == frame2;
69 }
70 
71 Transforms::~Transforms() = default;
72 
73 const std::string& Transforms::getTargetFrame() const
74 {
75  return target_frame_;
76 }
77 
79 {
80  return transforms_map_;
81 }
82 
84 {
85  for (const auto& t : transforms)
86  {
87  ASSERT_ISOMETRY(t.second) // unsanitized input, could contain a non-isometry
88  }
89  transforms_map_ = transforms;
90 }
91 
92 bool Transforms::isFixedFrame(const std::string& frame) const
93 {
94  if (frame.empty())
95  return false;
96  else
97  return transforms_map_.find(frame) != transforms_map_.end();
98 }
99 
100 const Eigen::Isometry3d& Transforms::getTransform(const std::string& from_frame) const
101 {
102  if (!from_frame.empty())
103  {
104  FixedTransformsMap::const_iterator it = transforms_map_.find(from_frame);
105  if (it != transforms_map_.end())
106  return it->second;
107  // If no transform found in map, return identity
108  }
109 
110  RCLCPP_ERROR(LOGGER, "Unable to transform from frame '%s' to frame '%s'. Returning identity.", from_frame.c_str(),
111  target_frame_.c_str());
112 
113  // return identity
114  static const Eigen::Isometry3d IDENTITY = Eigen::Isometry3d::Identity();
115  return IDENTITY;
116 }
117 
118 bool Transforms::canTransform(const std::string& from_frame) const
119 {
120  if (from_frame.empty())
121  return false;
122  else
123  return transforms_map_.find(from_frame) != transforms_map_.end();
124 }
125 
126 void Transforms::setTransform(const Eigen::Isometry3d& t, const std::string& from_frame)
127 {
128  ASSERT_ISOMETRY(t) // unsanitized input, could contain a non-isometry
129  if (from_frame.empty())
130  {
131  RCLCPP_ERROR(LOGGER, "Cannot record transform with empty name");
132  }
133  else
134  transforms_map_[from_frame] = t;
135 }
136 
137 void Transforms::setTransform(const geometry_msgs::msg::TransformStamped& transform)
138 {
139  if (sameFrame(transform.child_frame_id, target_frame_))
140  {
141  // convert message manually to ensure correct normalization for double (error < 1e-12)
142  // tf2 only enforces float normalization (error < 1e-5)
143  const auto& trans = transform.transform.translation;
144  const auto& rot = transform.transform.rotation;
145  Eigen::Translation3d translation(trans.x, trans.y, trans.z);
146  Eigen::Quaterniond rotation(rot.w, rot.x, rot.y, rot.z);
147  rotation.normalize();
148 
149  setTransform(translation * rotation, transform.header.frame_id);
150  }
151  else
152  {
153  RCLCPP_ERROR(LOGGER, "Given transform is to frame '%s', but frame '%s' was expected.",
154  transform.child_frame_id.c_str(), target_frame_.c_str());
155  }
156 }
157 
158 void Transforms::setTransforms(const std::vector<geometry_msgs::msg::TransformStamped>& transforms)
159 {
160  for (const geometry_msgs::msg::TransformStamped& transform : transforms)
161  setTransform(transform);
162 }
163 
164 void Transforms::copyTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms) const
165 {
166  transforms.resize(transforms_map_.size());
167  std::size_t i = 0;
168  for (FixedTransformsMap::const_iterator it = transforms_map_.begin(); it != transforms_map_.end(); ++it, ++i)
169  {
170  transforms[i] = tf2::eigenToTransform(it->second);
171  transforms[i].child_frame_id = target_frame_;
172  transforms[i].header.frame_id = it->first;
173  }
174 }
175 
176 } // end of namespace core
177 } // end of namespace moveit
void setTransforms(const std::vector< geometry_msgs::msg::TransformStamped > &transforms)
Set a transform in the transform tree (adding it if necessary)
Definition: transforms.cpp:158
const std::string & getTargetFrame() const
Get the planning frame corresponding to this set of transforms.
Definition: transforms.cpp:73
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
Definition: transforms.cpp:64
Transforms(const Transforms &)=delete
Transforms cannot be copy-constructed.
virtual ~Transforms()
Destructor.
std::string target_frame_
Definition: transforms.h:210
void setTransform(const Eigen::Isometry3d &t, const std::string &from_frame)
Set a transform in the transform tree (adding it if necessary)
Definition: transforms.cpp:126
const FixedTransformsMap & getAllTransforms() const
Return all the transforms.
Definition: transforms.cpp:78
virtual const Eigen::Isometry3d & getTransform(const std::string &from_frame) const
Get transform for from_frame (w.r.t target frame)
Definition: transforms.cpp:100
void copyTransforms(std::vector< geometry_msgs::msg::TransformStamped > &transforms) const
Get a vector of all the transforms as ROS messages.
Definition: transforms.cpp:164
void setAllTransforms(const FixedTransformsMap &transforms)
Set all the transforms: a map from string names of frames to corresponding Eigen::Isometry3d (w....
Definition: transforms.cpp:83
virtual bool isFixedFrame(const std::string &frame) const
Check whether a frame stays constant as the state of the robot model changes. This is true for any tr...
Definition: transforms.cpp:92
FixedTransformsMap transforms_map_
Definition: transforms.h:211
virtual bool canTransform(const std::string &from_frame) const
Check whether data can be transformed from a particular frame.
Definition: transforms.cpp:118
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...
Definition: transforms.h:53
Main namespace for MoveIt.
Definition: exceptions.h:43