serialize_msg.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 
37 #pragma once
38 
39 #include <ros/ros.h>
40 #include <Python.h>
41 #include <boost/python.hpp>
42 #include <string>
43 #include <stdexcept>
44 #include <type_traits>
45 
46 namespace moveit
47 {
48 namespace py_bindings_tools
49 {
51 class ByteString : public boost::python::object
52 {
53 public:
54  // constructors for bp::handle and friends
55  BOOST_PYTHON_FORWARD_OBJECT_CONSTRUCTORS(ByteString, boost::python::object)
56  ByteString() : boost::python::object(boost::python::handle<>(PyBytes_FromString("")))
57  {
58  }
59  explicit ByteString(const char* s) : boost::python::object(boost::python::handle<>(PyBytes_FromString(s)))
60  {
61  }
62  explicit ByteString(const std::string& s)
63  : boost::python::object(boost::python::handle<>(PyBytes_FromStringAndSize(s.c_str(), s.size())))
64  {
65  }
66  // bp::list[] returns a proxy which has to be converted to an object first
67  template <typename T>
68  explicit ByteString(const boost::python::api::proxy<T>& proxy) : boost::python::object(proxy)
69  {
70  }
74  template <typename T, typename std::enable_if<ros::message_traits::IsMessage<T>::value, int>::type = 0>
75  explicit ByteString(const T& msg)
76  : boost::python::object(
77  boost::python::handle<>(PyBytes_FromStringAndSize(nullptr, ros::serialization::serializationLength(msg))))
78  {
79  ros::serialization::OStream stream_arg(reinterpret_cast<uint8_t*>(PyBytes_AS_STRING(ptr())),
80  PyBytes_GET_SIZE(ptr()));
81  ros::serialization::serialize(stream_arg, msg);
82  }
83 
85  template <typename T>
86  void deserialize(T& msg) const
87  {
88  static_assert(sizeof(uint8_t) == sizeof(char), "ros/python buffer layout mismatch");
89  char* buf = PyBytes_AsString(ptr());
90  // buf == NULL on error
91  if (!buf)
92  {
93  throw std::runtime_error("Underlying python object is not a Bytes/String instance");
94  }
95  // unfortunately no constructor with const uint8_t
96  ros::serialization::IStream stream_arg(reinterpret_cast<uint8_t*>(buf), PyBytes_GET_SIZE(ptr()));
97  ros::serialization::deserialize(stream_arg, msg);
98  }
99 };
100 
102 template <typename T>
103 ByteString serializeMsg(const T& msg)
104 {
105  return ByteString(msg);
106 }
107 
109 template <typename T>
110 void deserializeMsg(const ByteString& data, T& msg)
111 {
112  data.deserialize(msg);
113 }
114 
115 } // namespace py_bindings_tools
116 } // namespace moveit
117 
118 namespace boost
119 {
120 namespace python
121 {
122 namespace converter
123 {
124 // only accept Python 3 Bytes / Python 2 String instance when used as C++ function parameter
125 template <>
126 struct object_manager_traits<moveit::py_bindings_tools::ByteString>
127 #if PY_VERSION_HEX >= 0x03000000
128  : pytype_object_manager_traits<&PyBytes_Type, moveit::py_bindings_tools::ByteString>
129 #else
130  : pytype_object_manager_traits<&PyString_Type, moveit::py_bindings_tools::ByteString>
131 #endif
132 
133 {
134 };
135 } // namespace converter
136 } // namespace python
137 } // namespace boost
ros::serialization::OStream
moveit::py_bindings_tools::ByteString::deserialize
void deserialize(T &msg) const
Convert content to a ROS message.
Definition: serialize_msg.h:182
ros::serialization::deserialize
void deserialize(Stream &stream, boost::array< T, N > &t)
s
XmlRpcServer s
ros
ros.h
PyBytes_AsString
#define PyBytes_AsString
serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
data
data
boost
ros::serialization::IStream
moveit::py_bindings_tools::ByteString::ByteString
ByteString()
Definition: serialize_msg.h:152
python
uint8_t
uint8_t
moveit
moveit::py_bindings_tools::deserializeMsg
void deserializeMsg(const ByteString &data, T &msg)
Convert a Python Bytestring to a ROS message.
Definition: serialize_msg.h:174
ros::serialization::serialize
void serialize(Stream &stream, const boost::array< T, N > &t)
moveit::py_bindings_tools::serializeMsg
ByteString serializeMsg(const T &msg)
Convert a ROS message to a Python Bytestring.
Definition: serialize_msg.h:167


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:17