serialize_msg_python_cpp_helpers.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, RWTH Aachen University.
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 RWTH Aachen University 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: Bjarne von Horn */
36 
37 #include <Python.h>
38 #include <boost/python.hpp>
40 #include <geometry_msgs/Vector3.h>
41 #include <cstring>
42 
43 namespace bp = boost::python;
45 
46 // Helper class to be exposed to Python
48 {
49  // Helper to test whether a vector of unsigned chars has the same content as a bytes Object
50  bool doCompare(const std::vector<unsigned char>& data, PyObject* obj)
51  {
52  const char* py_data = PyBytes_AsString(obj);
53  if (!py_data)
54  return false;
55  Py_ssize_t size = PyBytes_GET_SIZE(obj);
56  if (size < 0 || std::vector<unsigned char>::size_type(size) != data.size())
57  return false;
58  return std::memcmp(py_data, &data[0], size) == 0;
59  }
60 
61 public:
63  {
64  const std::vector<unsigned char> testdata{ 0xff, 0xef, 0x00, 0x10 };
65  return doCompare(testdata, s.ptr());
66  }
67  bool compareTuple(const bp::tuple& t)
68  {
69  const ByteString s(t[0]);
70  const std::vector<unsigned char> testdata{ 'm', 'n', 'o' };
71  return doCompare(testdata, s.ptr());
72  }
73 
75  {
76  return ByteString("abcdef");
77  }
79  {
80  std::string s;
81  s.push_back('\xff');
82  s.push_back('\xfe');
83  s.push_back('\x10');
84  s.push_back('\x00');
85  s.push_back('\x00');
86  return ByteString(s);
87  }
89  {
90  return ByteString();
91  }
92  bp::tuple getTuple()
93  {
94  return bp::make_tuple(ByteString("abcdef"));
95  }
97  {
98  geometry_msgs::Vector3 v;
99  v.x = 1.0;
100  v.y = -2.0;
101  v.z = 0.25;
102  return ByteString(v);
103  }
104  bool compareVector(const ByteString& s)
105  {
106  geometry_msgs::Vector3 v;
107  s.deserialize(v);
108  return v.x == 1.0 && v.y == -2.0 && v.z == 0.25;
109  }
110  bool compareVectorTuple(const bp::tuple& t)
111  {
112  const ByteString s(t[0]);
113  return compareVector(s);
114  }
115 
116  static void setup()
117  {
118  bp::class_<ByteStringTestHelper> cls("ByteStringTestHelper");
119  cls.def("compareEmbeddedZeros", &ByteStringTestHelper::compareEmbeddedZeros);
120  cls.def("compareTuple", &ByteStringTestHelper::compareTuple);
121  cls.def("compareVectorTuple", &ByteStringTestHelper::compareVectorTuple);
122  cls.def("getBytesPChar", &ByteStringTestHelper::getBytesPChar);
123  cls.def("getBytesStdString", &ByteStringTestHelper::getBytesStdString);
124  cls.def("getDefaultBytes", &ByteStringTestHelper::getDefaultBytes);
125  cls.def("getTuple", &ByteStringTestHelper::getTuple);
126  cls.def("getVector", &ByteStringTestHelper::getVector);
127  cls.def("compareVector", &ByteStringTestHelper::compareVector);
128  }
129 };
130 
131 BOOST_PYTHON_MODULE(_moveit_planning_interface_test_serialize_msg_cpp_helper)
132 {
134 }
ByteStringTestHelper::doCompare
bool doCompare(const std::vector< unsigned char > &data, PyObject *obj)
Definition: serialize_msg_python_cpp_helpers.cpp:50
ByteStringTestHelper
Definition: serialize_msg_python_cpp_helpers.cpp:47
boost::python
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(_moveit_planning_interface_test_serialize_msg_cpp_helper)
Definition: serialize_msg_python_cpp_helpers.cpp:131
s
XmlRpcServer s
ByteStringTestHelper::getTuple
bp::tuple getTuple()
Definition: serialize_msg_python_cpp_helpers.cpp:92
PyBytes_AsString
#define PyBytes_AsString
ByteStringTestHelper::setup
static void setup()
Definition: serialize_msg_python_cpp_helpers.cpp:116
data
data
ByteStringTestHelper::compareTuple
bool compareTuple(const bp::tuple &t)
Definition: serialize_msg_python_cpp_helpers.cpp:67
ByteStringTestHelper::compareEmbeddedZeros
bool compareEmbeddedZeros(const ByteString &s)
Definition: serialize_msg_python_cpp_helpers.cpp:62
ByteStringTestHelper::getBytesPChar
ByteString getBytesPChar()
Definition: serialize_msg_python_cpp_helpers.cpp:74
obj
CollisionObject< S > * obj
serialize_msg.h
t
tuple t
ByteStringTestHelper::compareVectorTuple
bool compareVectorTuple(const bp::tuple &t)
Definition: serialize_msg_python_cpp_helpers.cpp:110
ByteStringTestHelper::getDefaultBytes
ByteString getDefaultBytes()
Definition: serialize_msg_python_cpp_helpers.cpp:88
ByteStringTestHelper::getVector
ByteString getVector()
Definition: serialize_msg_python_cpp_helpers.cpp:96
ByteStringTestHelper::getBytesStdString
ByteString getBytesStdString()
Definition: serialize_msg_python_cpp_helpers.cpp:78
v
v
ByteStringTestHelper::compareVector
bool compareVector(const ByteString &s)
Definition: serialize_msg_python_cpp_helpers.cpp:104
moveit::py_bindings_tools::ByteString
C++ Wrapper class for Python 3 Bytes Object.
Definition: serialize_msg.h:115


planning_interface
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:30:20