moveit2
The MoveIt Motion Planning Framework for ROS 2.
ros_msg_typecasters.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, Peter David Fagan, Robert Haschke
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  * * The name of Robert Haschke may not be use to endorse or promote
18  * products derived from this software without specific prior
19  * 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, Robert Haschke */
36 
37 #pragma once
38 
39 #include <pybind11/pybind11.h>
40 #include <rclcpp/rclcpp.hpp>
41 #include <rclcpp/serialization.hpp>
42 #include <rclcpp/duration.hpp>
43 
44 namespace py = pybind11;
45 
46 namespace moveit_py
47 {
48 namespace moveit_py_utils
49 {
50 PYBIND11_EXPORT pybind11::object createMessage(const std::string& ros_msg_name);
51 PYBIND11_EXPORT bool convertible(const pybind11::handle& h, const std::string& ros_msg_name);
52 } // namespace moveit_py_utils
53 } // namespace moveit_py
54 
55 namespace pybind11
56 {
57 namespace detail
58 {
59 // Base class for type conversion (C++ <-> python) of ROS message types
60 template <typename T>
62 {
63  // C++ -> Python
64  // TODO: add error handling
65  static handle cast(const T& src, return_value_policy /* policy */, handle /* parent */)
66  {
67  // serialize src
68  rclcpp::Serialization<T> serializer;
69  rclcpp::SerializedMessage serialized_msg;
70  serializer.serialize_message(&src, &serialized_msg);
71  py::bytes bytes = py::bytes(reinterpret_cast<const char*>(serialized_msg.get_rcl_serialized_message().buffer),
72  serialized_msg.get_rcl_serialized_message().buffer_length);
73 
74  // get Python object type
75  const std::string ros_msg_name = rosidl_generator_traits::name<T>();
76 
77  // find delimiting '/' in ros_msg_name
78  std::size_t pos1 = ros_msg_name.find('/');
79  std::size_t pos2 = ros_msg_name.find('/', pos1 + 1);
80  py::module m = py::module::import((ros_msg_name.substr(0, pos1) + ".msg").c_str());
81 
82  // retrieve type instance
83  py::object cls = m.attr(ros_msg_name.substr(pos2 + 1).c_str());
84 
85  // deserialize into python object
86  py::module rclpy = py::module::import("rclpy.serialization");
87  py::object msg = rclpy.attr("deserialize_message")(bytes, cls);
88 
89  return msg.release();
90  }
91 
92  // Python -> C++
93  bool load(handle src, bool /*convert*/)
94  {
95  // check datatype of src
96  if (!moveit_py::moveit_py_utils::convertible(src, rosidl_generator_traits::name<T>()))
97  return false;
98 
99  // serialize src into python buffer
100  py::module rclpy = py::module::import("rclpy.serialization");
101  py::bytes bytes = rclpy.attr("serialize_message")(src);
102 
103  // deserialize into C++ object
104  rcl_serialized_message_t rcl_serialized_msg = rmw_get_zero_initialized_serialized_message();
105  char* serialized_buffer;
106  Py_ssize_t length;
107  if (PYBIND11_BYTES_AS_STRING_AND_SIZE(bytes.ptr(), &serialized_buffer, &length))
108  {
109  throw py::error_already_set();
110  }
111  if (length < 0)
112  {
113  throw py::error_already_set();
114  }
115  rcl_serialized_msg.buffer_capacity = length;
116  rcl_serialized_msg.buffer_length = length;
117  rcl_serialized_msg.buffer = reinterpret_cast<uint8_t*>(serialized_buffer);
118  rmw_ret_t rmw_ret =
119  rmw_deserialize(&rcl_serialized_msg, rosidl_typesupport_cpp::get_message_type_support_handle<T>(), &value);
120  if (RMW_RET_OK != rmw_ret)
121  {
122  throw std::runtime_error("failed to deserialize ROS message");
123  }
124  return true;
125  }
126 
128 };
129 
130 template <typename T>
131 struct type_caster<T, enable_if_t<rosidl_generator_traits::is_message<T>::value>> : RosMsgTypeCaster<T>
132 {
133 };
134 
135 } // namespace detail
136 } // namespace pybind11
PYBIND11_EXPORT bool convertible(const pybind11::handle &h, const std::string &ros_msg_name)
PYBIND11_EXPORT pybind11::object createMessage(const std::string &ros_msg_name)
static handle cast(const T &src, return_value_policy, handle)