moveit2
The MoveIt Motion Planning Framework for ROS 2.
copy_ros_msg.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, Peter David Fagan
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 PickNik Inc. 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: Peter David Fagan */
36 
37 #include <list>
39 
40 namespace moveit_py
41 {
42 namespace moveit_py_utils
43 {
44 // Ros Message Copy Definitions (Note: copying faster than serialize/deserialize)
45 
46 geometry_msgs::msg::PoseStamped poseStampedToCpp(const py::object& pose_stamped)
47 {
48  // recreate instance in C++ using python object data
49  geometry_msgs::msg::PoseStamped pose_stamped_cpp;
50  pose_stamped_cpp.header.frame_id = pose_stamped.attr("header").attr("frame_id").cast<std::string>();
51  pose_stamped_cpp.pose = poseToCpp(pose_stamped.attr("pose"));
52  return pose_stamped_cpp;
53 }
54 
55 geometry_msgs::msg::Pose poseToCpp(const py::object& pose)
56 {
57  // recreate instance in C++ using python object data
58  geometry_msgs::msg::Pose pose_cpp;
59  pose_cpp.orientation.w = pose.attr("orientation").attr("w").cast<double>();
60  pose_cpp.orientation.x = pose.attr("orientation").attr("x").cast<double>();
61  pose_cpp.orientation.y = pose.attr("orientation").attr("y").cast<double>();
62  pose_cpp.orientation.z = pose.attr("orientation").attr("z").cast<double>();
63  pose_cpp.position.x = pose.attr("position").attr("x").cast<double>();
64  pose_cpp.position.y = pose.attr("position").attr("y").cast<double>();
65  pose_cpp.position.z = pose.attr("position").attr("z").cast<double>();
66 
67  return pose_cpp;
68 }
69 
70 py::object poseToPy(geometry_msgs::msg::Pose pose)
71 {
72  // recreate instance in Python using C++ object data
73  py::object pose_py = py::module_::import("geometry_msgs.msg").attr("Pose")();
74 
75  pose_py.attr("orientation").attr("w") = pose.orientation.w;
76  pose_py.attr("orientation").attr("x") = pose.orientation.x;
77  pose_py.attr("orientation").attr("y") = pose.orientation.y;
78  pose_py.attr("orientation").attr("z") = pose.orientation.z;
79  pose_py.attr("position").attr("x") = pose.position.x;
80  pose_py.attr("position").attr("y") = pose.position.y;
81  pose_py.attr("position").attr("z") = pose.position.z;
82 
83  return pose_py;
84 }
85 
86 geometry_msgs::msg::Point pointToCpp(const py::object& point)
87 {
88  // recreate instance in C++ using python object data
89  geometry_msgs::msg::Point point_cpp;
90  point_cpp.x = point.attr("x").cast<double>();
91  point_cpp.y = point.attr("y").cast<double>();
92  point_cpp.z = point.attr("z").cast<double>();
93 
94  return point_cpp;
95 }
96 
97 geometry_msgs::msg::Vector3 vector3ToCpp(const py::object& vector3)
98 {
99  // recreate instance in C++ using python object data
100  geometry_msgs::msg::Vector3 vector3_cpp;
101  vector3_cpp.x = vector3.attr("x").cast<double>();
102  vector3_cpp.y = vector3.attr("y").cast<double>();
103  vector3_cpp.z = vector3.attr("z").cast<double>();
104 
105  return vector3_cpp;
106 }
107 
108 geometry_msgs::msg::Quaternion quaternionToCpp(const py::object& quaternion)
109 {
110  // recreate instance in C++ using python object data
111  geometry_msgs::msg::Quaternion quaternion_cpp;
112  quaternion_cpp.w = quaternion.attr("w").cast<double>();
113  quaternion_cpp.x = quaternion.attr("x").cast<double>();
114  quaternion_cpp.y = quaternion.attr("y").cast<double>();
115  quaternion_cpp.z = quaternion.attr("z").cast<double>();
116 
117  return quaternion_cpp;
118 }
119 
120 shape_msgs::msg::SolidPrimitive solidPrimitiveToCpp(const py::object& primitive)
121 {
122  // recreate instance in C++ using python object data
123  shape_msgs::msg::SolidPrimitive primitive_cpp;
124  primitive_cpp.type = primitive.attr("type").cast<int>();
125  for (auto& dimension : primitive.attr("dimensions"))
126  {
127  primitive_cpp.dimensions.push_back(py::reinterpret_borrow<py::object>(dimension).cast<double>());
128  }
129 
130  return primitive_cpp;
131 }
132 
133 shape_msgs::msg::MeshTriangle meshTriangleToCpp(const py::object& mesh_triangle)
134 {
135  // recreate instance in C++ using python object data
136  shape_msgs::msg::MeshTriangle mesh_triangle_cpp;
137  mesh_triangle_cpp.vertex_indices[0] = mesh_triangle.attr("vertex_indices").attr("__getitem__")(0).cast<int>();
138  mesh_triangle_cpp.vertex_indices[1] = mesh_triangle.attr("vertex_indices").attr("__getitem__")(1).cast<int>();
139  mesh_triangle_cpp.vertex_indices[2] = mesh_triangle.attr("vertex_indices").attr("__getitem__")(2).cast<int>();
140 
141  return mesh_triangle_cpp;
142 }
143 
144 shape_msgs::msg::Mesh meshToCpp(const py::object& mesh)
145 {
146  // recreate instance in C++ using python object data
147  shape_msgs::msg::Mesh mesh_cpp;
148  mesh_cpp.vertices.resize(mesh.attr("vertices").attr("__len__")().cast<int>());
149  for (const auto& vertex : mesh.attr("vertices"))
150  {
151  mesh_cpp.vertices.push_back(pointToCpp(py::reinterpret_borrow<py::object>(vertex)));
152  }
153  mesh_cpp.triangles.resize(mesh.attr("triangles").attr("__len__")().cast<int>());
154  for (const auto& triangle : mesh.attr("triangles"))
155  {
156  mesh_cpp.triangles.push_back(meshTriangleToCpp(py::reinterpret_borrow<py::object>(triangle)));
157  }
158 
159  return mesh_cpp;
160 }
161 
162 moveit_msgs::msg::BoundingVolume boundingVolumeToCpp(const py::object& bounding_volume)
163 {
164  // recreate instance in C++ using python object data
165  moveit_msgs::msg::BoundingVolume bounding_volume_cpp;
166 
167  // primitives
168  for (const auto& primitive : bounding_volume.attr("primitives"))
169  {
170  bounding_volume_cpp.primitives.push_back(solidPrimitiveToCpp(py::reinterpret_borrow<py::object>(primitive)));
171  }
172 
173  // primitive poses
174  for (const auto& primitive_pose : bounding_volume.attr("primitive_poses"))
175  {
176  bounding_volume_cpp.primitive_poses.push_back(poseToCpp(py::reinterpret_borrow<py::object>(primitive_pose)));
177  }
178 
179  // meshes
180  for (const auto& mesh : bounding_volume.attr("meshes"))
181  {
182  bounding_volume_cpp.meshes.push_back(meshToCpp(py::reinterpret_borrow<py::object>(mesh)));
183  }
184 
185  // mesh poses
186  for (const auto& mesh_poses : bounding_volume.attr("mesh_poses"))
187  {
188  bounding_volume_cpp.mesh_poses.push_back(poseToCpp(py::reinterpret_borrow<py::object>(mesh_poses)));
189  }
190 
191  return bounding_volume_cpp;
192 }
193 
194 moveit_msgs::msg::JointConstraint jointConstraintToCpp(const py::object& joint_constraint)
195 {
196  // recreate instance in C++ using python object data
197  moveit_msgs::msg::JointConstraint joint_constraint_cpp;
198  joint_constraint_cpp.joint_name = joint_constraint.attr("joint_name").cast<std::string>();
199  joint_constraint_cpp.position = joint_constraint.attr("position").cast<double>();
200  joint_constraint_cpp.tolerance_above = joint_constraint.attr("tolerance_above").cast<double>();
201  joint_constraint_cpp.tolerance_below = joint_constraint.attr("tolerance_below").cast<double>();
202  joint_constraint_cpp.weight = joint_constraint.attr("weight").cast<double>();
203 
204  return joint_constraint_cpp;
205 }
206 
207 moveit_msgs::msg::PositionConstraint positionConstraintToCpp(const py::object& position_constraint)
208 {
209  // recreate instance in C++ using python object data
210  moveit_msgs::msg::PositionConstraint position_constraint_cpp;
211  position_constraint_cpp.header.frame_id = position_constraint.attr("header").attr("frame_id").cast<std::string>();
212  position_constraint_cpp.link_name = position_constraint.attr("link_name").cast<std::string>();
213  position_constraint_cpp.target_point_offset = vector3ToCpp(position_constraint.attr("target_point_offset"));
214  position_constraint_cpp.constraint_region = boundingVolumeToCpp(position_constraint.attr("constraint_region"));
215  position_constraint_cpp.weight = position_constraint.attr("weight").cast<double>();
216 
217  return position_constraint_cpp;
218 }
219 
220 moveit_msgs::msg::OrientationConstraint orientationConstraintToCpp(const py::object& orientation_constraint)
221 {
222  // recreate instance in C++ using python object data
223  moveit_msgs::msg::OrientationConstraint orientation_constraint_cpp;
224  orientation_constraint_cpp.header.frame_id =
225  orientation_constraint.attr("header").attr("frame_id").cast<std::string>();
226  orientation_constraint_cpp.link_name = orientation_constraint.attr("link_name").cast<std::string>();
227  orientation_constraint_cpp.orientation = quaternionToCpp(orientation_constraint.attr("target_quaternion"));
228  orientation_constraint_cpp.absolute_x_axis_tolerance =
229  orientation_constraint.attr("absolute_x_axis_tolerance").cast<double>();
230  orientation_constraint_cpp.absolute_y_axis_tolerance =
231  orientation_constraint.attr("absolute_y_axis_tolerance").cast<double>();
232  orientation_constraint_cpp.absolute_z_axis_tolerance =
233  orientation_constraint.attr("absolute_z_axis_tolerance").cast<double>();
234  orientation_constraint_cpp.parameterization = orientation_constraint.attr("parameterization").cast<int>();
235  orientation_constraint_cpp.weight = orientation_constraint.attr("weight").cast<double>();
236 
237  return orientation_constraint_cpp;
238 }
239 
240 moveit_msgs::msg::VisibilityConstraint visibilityConstraintToCpp(const py::object& visibility_constraint)
241 {
242  // recreate instance in C++ using python object data
243  moveit_msgs::msg::VisibilityConstraint visibility_constraint_cpp;
244  visibility_constraint_cpp.target_radius = visibility_constraint.attr("target_radius").cast<double>();
245  visibility_constraint_cpp.target_pose = poseStampedToCpp(visibility_constraint.attr("target_pose"));
246  visibility_constraint_cpp.cone_sides = visibility_constraint.attr("cone_sides").cast<int>();
247  visibility_constraint_cpp.sensor_pose = poseStampedToCpp(visibility_constraint.attr("sensor_pose"));
248  visibility_constraint_cpp.max_view_angle = visibility_constraint.attr("max_view_angle").cast<double>();
249  visibility_constraint_cpp.max_range_angle = visibility_constraint.attr("max_range_angle").cast<double>();
250  visibility_constraint_cpp.sensor_view_direction = visibility_constraint.attr("sensor_view_direction").cast<int>();
251  visibility_constraint_cpp.weight = visibility_constraint.attr("weight").cast<double>();
252 
253  return visibility_constraint_cpp;
254 }
255 
256 moveit_msgs::msg::CollisionObject collisionObjectToCpp(const py::object& collision_object)
257 {
258  // recreate instance in C++ using python object data
259  moveit_msgs::msg::CollisionObject collision_object_cpp;
260 
261  // header
262  collision_object_cpp.header.frame_id = collision_object.attr("header").attr("frame_id").cast<std::string>();
263 
264  // object pose
265  collision_object_cpp.pose = poseToCpp(collision_object.attr("pose"));
266 
267  // object id
268  collision_object_cpp.id = collision_object.attr("id").cast<std::string>();
269 
270  // object type
271  collision_object_cpp.type.key = collision_object.attr("type").attr("key").cast<std::string>();
272  collision_object_cpp.type.db = collision_object.attr("type").attr("db").cast<std::string>();
273 
274  // iterate through python list creating C++ vector of primitives
275  for (const auto& primitive : collision_object.attr("primitives"))
276  {
277  auto primitive_cpp = solidPrimitiveToCpp(py::reinterpret_borrow<py::object>(primitive));
278  collision_object_cpp.primitives.push_back(primitive_cpp);
279  }
280 
281  // iterate through python list creating C++ vector of primitive poses
282  for (const auto& primitive_pose : collision_object.attr("primitive_poses"))
283  {
284  auto primitive_pose_cpp = poseToCpp(py::reinterpret_borrow<py::object>(primitive_pose));
285  collision_object_cpp.primitive_poses.push_back(primitive_pose_cpp);
286  }
287 
288  // iterate through python list creating C++ vector of meshes
289  for (const auto& mesh : collision_object.attr("meshes"))
290  {
291  // TODO (peterdavidfagan): implement mesh conversion
292  auto mesh_cpp = meshToCpp(py::reinterpret_borrow<py::object>(mesh));
293  collision_object_cpp.meshes.push_back(mesh_cpp);
294  }
295 
296  // iterate through python list creating C++ vector of mesh poses
297  for (const auto& mesh_pose : collision_object.attr("mesh_poses"))
298  {
299  auto mesh_pose_cpp = poseToCpp(py::reinterpret_borrow<py::object>(mesh_pose));
300  collision_object_cpp.mesh_poses.push_back(mesh_pose_cpp);
301  }
302 
303  // operation
304  collision_object_cpp.operation = collision_object.attr("operation").cast<char>();
305 
306  return collision_object_cpp;
307 }
308 
309 moveit_msgs::msg::Constraints constraintsToCpp(const py::object& constraints)
310 {
311  // recreate instance in C++ using python object data
312  moveit_msgs::msg::Constraints constraints_cpp;
313 
314  // iterate through python list creating C++ vector of joint constraints
315  for (const auto& joint_constraint : constraints.attr("joint_constraints"))
316  {
317  auto joint_constraint_cpp = jointConstraintToCpp(py::reinterpret_borrow<py::object>(joint_constraint));
318  constraints_cpp.joint_constraints.push_back(joint_constraint_cpp);
319  }
320 
321  // iterate through python list creating C++ vector of position constraints
322  for (const auto& position_constraint : constraints.attr("position_constraints"))
323  {
324  auto position_constraint_cpp = positionConstraintToCpp(py::reinterpret_borrow<py::object>(position_constraint));
325  constraints_cpp.position_constraints.push_back(position_constraint_cpp);
326  }
327 
328  // iterate through python list creating C++ vector of orientation constraints
329  for (const auto& orientation_constraint : constraints.attr("orientation_constraints"))
330  {
331  auto orientation_constraint_cpp =
332  orientationConstraintToCpp(py::reinterpret_borrow<py::object>(orientation_constraint));
333  constraints_cpp.orientation_constraints.push_back(orientation_constraint_cpp);
334  }
335 
336  // iterate through python list creating C++ vector of visibility constraints
337  for (const auto& visibility_constraint : constraints.attr("visibility_constraints"))
338  {
339  auto visibility_constraint_cpp =
340  visibilityConstraintToCpp(py::reinterpret_borrow<py::object>(visibility_constraint));
341  constraints_cpp.visibility_constraints.push_back(visibility_constraint_cpp);
342  }
343 
344  return constraints_cpp;
345 }
346 } // namespace moveit_py_utils
347 } // namespace moveit_py
geometry_msgs::msg::Quaternion quaternionToCpp(const py::object &quaternion)
shape_msgs::msg::Mesh meshToCpp(const py::object &mesh)
moveit_msgs::msg::PositionConstraint positionConstraintToCpp(const py::object &position_constraint)
shape_msgs::msg::MeshTriangle meshTriangleToCpp(const py::object &mesh_triangle)
moveit_msgs::msg::Constraints constraintsToCpp(const py::object &constraints)
geometry_msgs::msg::Vector3 vector3ToCpp(const py::object &vector3)
moveit_msgs::msg::BoundingVolume boundingVolumeToCpp(const py::object &bounding_volume)
geometry_msgs::msg::Pose poseToCpp(const py::object &pose)
moveit_msgs::msg::OrientationConstraint orientationConstraintToCpp(const py::object &orientation_constraint)
py::object poseToPy(geometry_msgs::msg::Pose pose)
shape_msgs::msg::SolidPrimitive solidPrimitiveToCpp(const py::object &primitive)
moveit_msgs::msg::CollisionObject collisionObjectToCpp(const py::object &collision_object)
geometry_msgs::msg::PoseStamped poseStampedToCpp(const py::object &pose_stamped)
moveit_msgs::msg::VisibilityConstraint visibilityConstraintToCpp(const py::object &visibility_constraint)
geometry_msgs::msg::Point pointToCpp(const py::object &point)
moveit_msgs::msg::JointConstraint jointConstraintToCpp(const py::object &joint_constraint)