Skip to content

Commit 91bede1

Browse files
committed
Imported upstream version '1.0.0' of 'upstream'
1 parent 1b4503b commit 91bede1

11 files changed

+669
-0
lines changed

CHANGELOG.rst

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package py_binding_tools
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4+
5+
1.0.0 (2024-03-05)
6+
------------------
7+
* Initial release factored out from https://github.com/ros-planning/moveit/pull/2910

CMakeLists.txt

+47
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
cmake_minimum_required(VERSION 3.0.2)
2+
project(py_binding_tools)
3+
4+
find_package(catkin REQUIRED
5+
COMPONENTS
6+
geometry_msgs
7+
pybind11_catkin
8+
roscpp
9+
)
10+
11+
# catkin_python_setup()
12+
13+
catkin_package(
14+
INCLUDE_DIRS include
15+
LIBRARIES ${PROJECT_NAME}
16+
CATKIN_DEPENDS geometry_msgs roscpp
17+
)
18+
19+
include_directories(include ${catkin_INCLUDE_DIRS})
20+
21+
add_library(${PROJECT_NAME}
22+
src/ros_msg_typecasters.cpp
23+
src/roscpp_initializer.cpp
24+
)
25+
add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS})
26+
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${PYTHON_LIBRARIES})
27+
28+
install(
29+
TARGETS ${PROJECT_NAME}
30+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
31+
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
32+
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
33+
)
34+
35+
install(DIRECTORY include/${PROJECT_NAME}/
36+
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
37+
)
38+
39+
#catkin_lint cannot detect target declarations in functions, here in pybind11_add_module
40+
#catkin_lint: ignore undefined_target
41+
42+
pybind_add_module(${PROJECT_NAME}_module src/${PROJECT_NAME}.cpp)
43+
set_target_properties(${PROJECT_NAME}_module PROPERTIES OUTPUT_NAME ${PROJECT_NAME})
44+
target_link_libraries(${PROJECT_NAME}_module PRIVATE ${PROJECT_NAME})
45+
46+
install(TARGETS ${PROJECT_NAME}_module
47+
LIBRARY DESTINATION ${CATKIN_GLOBAL_PYTHON_DESTINATION})

LICENSE.txt

+29
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
BSD 3-Clause License
2+
3+
Copyright (c) 2020-2023, Bielefeld University
4+
All rights reserved.
5+
6+
Redistribution and use in source and binary forms, with or without
7+
modification, are permitted provided that the following conditions are met:
8+
9+
* Redistributions of source code must retain the above copyright notice, this
10+
list of conditions and the following disclaimer.
11+
12+
* Redistributions in binary form must reproduce the above copyright notice,
13+
this list of conditions and the following disclaimer in the documentation
14+
and/or other materials provided with the distribution.
15+
16+
* Neither the name of the copyright holder nor the names of its
17+
contributors may be used to endorse or promote products derived from
18+
this software without specific prior written permission.
19+
20+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21+
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22+
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23+
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28+
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29+
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

README.md

+34
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
## Python binding tools for C++
2+
3+
This package provides some tools to facilitate the generation of python bindings for C++ code, based on [pybind11](https://github.com/pybind/pybind11).
4+
5+
### Automatic type conversion for ROS message types
6+
7+
Conversion between native C++ and python types is performed via ROS message serialization and deserialization, which is implemented via C++ templates. It suffices to include:
8+
9+
```cpp
10+
#include <py_binding_tools/ros_msg_typecasters.h>
11+
```
12+
13+
The `PoseStamped` message from the `geometry_msgs` package also accepts a single string as an argument.
14+
In this case, the string is interpreted as the `header.frame_id` field of the message and the pose becomes the identity transform. To use this extension, include the following header instead:
15+
16+
```cpp
17+
#include <py_binding_tools/geometry_msg_typecasters.h>
18+
```
19+
20+
### C++ ROS initialization
21+
22+
C++ and Python use their own ROS implementations (`rospy` and `roscpp`).
23+
Thus, it is necessary to initialize ROS in the C++ domain additionally to the Python domain before calling any ROS-related functions from wrapped C++ functions or classes.
24+
To this end, the package provides the python function `roscpp_init()` and the C++ class `ROScppInitializer`. The latter is intended to be used as a base class for your python wrapper classes:
25+
26+
```cpp
27+
class FooWrapper : protected ROScppInitializer, public Foo {
28+
// ...
29+
};
30+
```
31+
32+
to ensure that the ROS infrastructure is initialized before usage in the wrapped C++ class. Ensure to list `ROScppInitializer` as the _first_ base class, if ROS functionality is required in the constructor already!
33+
34+
`ROScppInitializer` registers an anonymous C++ ROS node named `python_wrapper_xxx`. If you need a specific node name or if you want to pass remappings, use the manual initialization function `roscpp_init(name="", remappings={}, options=0)` instead, which effectively calls `ros::init` with the given arguments. Note, that an empty name will map to the above-mentioned node name `python_wrapper_xxx`.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2021, 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 used 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: Robert Haschke */
36+
37+
#pragma once
38+
39+
#include "ros_msg_typecasters.h"
40+
#include <geometry_msgs/PoseStamped.h>
41+
42+
namespace pybind11
43+
{
44+
namespace detail
45+
{
46+
/** Convienency type caster, also allowing to initialize PoseStamped from a string */
47+
template <>
48+
struct type_caster<geometry_msgs::PoseStamped> : RosMsgTypeCaster<geometry_msgs::PoseStamped>
49+
{
50+
// Python -> C++
51+
bool load(handle src, bool convert)
52+
{
53+
type_caster<std::string> str_caster;
54+
if (convert && str_caster.load(src, false))
55+
{ // string creates identity pose with given frame
56+
value.header.frame_id = static_cast<std::string&>(str_caster);
57+
value.pose.orientation.w = 1.0;
58+
return true;
59+
}
60+
return RosMsgTypeCaster<geometry_msgs::PoseStamped>::load(src, convert);
61+
}
62+
};
63+
64+
} // namespace detail
65+
} // namespace pybind11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,147 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2021, 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 used 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: Robert Haschke */
36+
37+
#pragma once
38+
39+
#include <pybind11/pybind11.h>
40+
#include <ros/duration.h>
41+
#include <ros/serialization.h>
42+
43+
/** Provide pybind11 type converters for ROS types */
44+
45+
namespace py_binding_tools
46+
{
47+
PYBIND11_EXPORT pybind11::object createMessage(const std::string& ros_msg_name);
48+
PYBIND11_EXPORT bool convertible(const pybind11::handle& h, const char* ros_msg_name);
49+
50+
/** Throws genpy.DeserializationError exception.
51+
*
52+
* This is a convenience method to support the old behaviour of returning
53+
* an empty ByteString.
54+
*/
55+
PYBIND11_EXPORT void throwDeserializationError [[noreturn]] ();
56+
57+
} // namespace py_binding_tools
58+
59+
namespace pybind11
60+
{
61+
namespace detail
62+
{
63+
/// Convert ros::Duration / ros::WallDuration into a float
64+
template <typename T>
65+
struct DurationCaster
66+
{
67+
// C++ -> Python
68+
static handle cast(T&& src, return_value_policy /* policy */, handle /* parent */)
69+
{
70+
return PyFloat_FromDouble(src.toSec());
71+
}
72+
73+
// Python -> C++
74+
bool load(handle src, bool convert)
75+
{
76+
if (hasattr(src, "to_sec"))
77+
{
78+
value = T(src.attr("to_sec")().cast<double>());
79+
}
80+
else if (convert)
81+
{
82+
value = T(src.cast<double>());
83+
}
84+
else
85+
return false;
86+
return true;
87+
}
88+
89+
PYBIND11_TYPE_CASTER(T, _("Duration"));
90+
};
91+
92+
template <>
93+
struct type_caster<ros::Duration> : DurationCaster<ros::Duration>
94+
{
95+
};
96+
97+
template <>
98+
struct type_caster<ros::WallDuration> : DurationCaster<ros::WallDuration>
99+
{
100+
};
101+
102+
/// Base class for type conversion (C++ <-> python) of ROS message types
103+
template <typename T>
104+
struct RosMsgTypeCaster
105+
{
106+
// C++ -> Python
107+
static handle cast(const T& src, return_value_policy /* policy */, handle /* parent */)
108+
{
109+
// serialize src into (python) buffer
110+
std::size_t size = ros::serialization::serializationLength(src);
111+
object pbuffer = reinterpret_steal<object>(PyBytes_FromStringAndSize(nullptr, size));
112+
ros::serialization::OStream stream(reinterpret_cast<uint8_t*>(PyBytes_AsString(pbuffer.ptr())), size);
113+
ros::serialization::serialize(stream, src);
114+
// deserialize python type from buffer
115+
object msg = py_binding_tools::createMessage(ros::message_traits::DataType<T>::value());
116+
msg.attr("deserialize")(pbuffer);
117+
return msg.release();
118+
}
119+
120+
// Python -> C++
121+
bool load(handle src, bool /*convert*/)
122+
{
123+
if (!py_binding_tools::convertible(src, ros::message_traits::DataType<T>::value()))
124+
return false;
125+
// serialize src into (python) buffer
126+
object pstream = module::import("io").attr("BytesIO")();
127+
src.attr("serialize")(pstream);
128+
object pbuffer = pstream.attr("getvalue")();
129+
// deserialize C++ type from buffer
130+
char* cbuffer = nullptr;
131+
Py_ssize_t size;
132+
PyBytes_AsStringAndSize(pbuffer.ptr(), &cbuffer, &size);
133+
ros::serialization::IStream cstream(const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cbuffer)), size);
134+
ros::serialization::deserialize(cstream, value);
135+
return true;
136+
}
137+
138+
PYBIND11_TYPE_CASTER(T, _<T>());
139+
};
140+
141+
template <typename T>
142+
struct type_caster<T, enable_if_t<ros::message_traits::IsMessage<T>::value>> : RosMsgTypeCaster<T>
143+
{
144+
};
145+
146+
} // namespace detail
147+
} // namespace pybind11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2020, Bielefeld 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 Bielefeld 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+
#pragma once
35+
36+
#include <ros/init.h>
37+
38+
namespace py_binding_tools
39+
{
40+
/** The constructor of this class ensures that ros::init() has been called.
41+
*
42+
* Thread safety and multiple initialization is properly handled.
43+
* The default node name is "python_wrapper".
44+
* If you like to have a custom name, use the roscpp_init() function before. */
45+
class ROScppInitializer
46+
{
47+
public:
48+
ROScppInitializer();
49+
~ROScppInitializer();
50+
};
51+
52+
void roscpp_init(const std::string& node_name,
53+
const std::map<std::string, std::string>& remappings,
54+
uint32_t options);
55+
56+
void roscpp_shutdown();
57+
58+
} // namespace py_binding_tools

0 commit comments

Comments
 (0)