Skip to content

Commit 62eb8be

Browse files
authored
Merge branch 'main' into ahcorde/python/particleemitter
2 parents 27a4ae4 + ea6ace6 commit 62eb8be

20 files changed

+238
-112
lines changed

.github/ci/packages.apt

+1
Original file line numberDiff line numberDiff line change
@@ -12,4 +12,5 @@ python3-distutils
1212
python3-ignition-math7
1313
python3-psutil
1414
python3-pybind11
15+
python3-pytest
1516
ruby-dev

python/CMakeLists.txt

+18-2
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@ pybind11_add_module(sdformat SHARED
7878
src/sdf/pySurface.cc
7979
src/sdf/pyVisual.cc
8080
src/sdf/pyWorld.cc
81+
src/sdf/pybind11_helpers.cc
8182
)
8283

8384
target_link_libraries(sdformat PRIVATE
@@ -138,10 +139,25 @@ if (BUILD_TESTING)
138139
pyVisual_TEST
139140
pyWorld_TEST
140141
)
142+
execute_process(COMMAND "${Python3_EXECUTABLE}" -m pytest --version
143+
OUTPUT_VARIABLE PYTEST_output
144+
ERROR_VARIABLE PYTEST_error
145+
RESULT_VARIABLE PYTEST_result)
146+
if(${PYTEST_result} EQUAL 0)
147+
set(pytest_FOUND TRUE)
148+
else()
149+
message("")
150+
message(WARNING "Pytest package not available: ${PYTEST_error}")
151+
endif()
141152

142153
foreach (test ${python_tests})
143-
add_test(NAME ${test}.py COMMAND
144-
"${Python3_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py")
154+
if (pytest_FOUND)
155+
add_test(NAME ${test}.py COMMAND
156+
"${Python3_EXECUTABLE}" -m pytest "${CMAKE_SOURCE_DIR}/python/test/${test}.py" --junitxml "${CMAKE_BINARY_DIR}/test_results/${test}.xml")
157+
else()
158+
add_test(NAME ${test}.py COMMAND
159+
"${Python3_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py")
160+
endif()
145161
set(_env_vars)
146162
list(APPEND _env_vars "PYTHONPATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}/python/:${CMAKE_BINARY_DIR}/lib:$ENV{PYTHONPATH}")
147163
list(APPEND _env_vars "LD_LIBRARY_PATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}:$ENV{LD_LIBRARY_PATH}")

python/src/sdf/pyFrame.cc

+2-5
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include "sdf/Frame.hh"
2323
#include "pyExceptions.hh"
24+
#include "pybind11_helpers.hh"
2425

2526
using namespace pybind11::literals;
2627

@@ -64,11 +65,7 @@ void defineFrame(pybind11::object module)
6465
[](const sdf::Frame &self)
6566
{
6667
std::string body;
67-
auto errors = self.ResolveAttachedToBody(body);
68-
if (!errors.empty())
69-
{
70-
throw PySDFErrorsException(errors);
71-
}
68+
ThrowIfErrors(self.ResolveAttachedToBody(body));
7269
return body;
7370
},
7471
"Resolve the attached-to body of this frame from the "

python/src/sdf/pyJoint.cc

+5-4
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include "sdf/Joint.hh"
2323
#include "sdf/Sensor.hh"
24+
#include "pybind11_helpers.hh"
2425

2526
using namespace pybind11::literals;
2627

@@ -57,17 +58,17 @@ void defineJoint(pybind11::object module)
5758
[](const sdf::Joint &self)
5859
{
5960
std::string link;
60-
auto errors = self.ResolveChildLink(link);
61-
return std::make_tuple(errors, link);
61+
ThrowIfErrors(self.ResolveChildLink(link));
62+
return link;
6263
},
6364
"Resolve the name of the child link from the "
6465
"FrameAttachedToGraph.")
6566
.def("resolve_parent_link",
6667
[](const sdf::Joint &self)
6768
{
6869
std::string link;
69-
auto errors = self.ResolveParentLink(link);
70-
return std::make_tuple(errors, link);
70+
ThrowIfErrors(self.ResolveParentLink(link));
71+
return link;
7172
},
7273
"Resolve the name of the parent link from the "
7374
"FrameAttachedToGraph. It will return the name of a link or "

python/src/sdf/pyJointAxis.cc

+11-3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <pybind11/stl.h>
2121

2222
#include "sdf/JointAxis.hh"
23+
#include "pybind11_helpers.hh"
2324

2425

2526
using namespace pybind11::literals;
@@ -38,7 +39,10 @@ void defineJointAxis(pybind11::object module)
3839
.def(pybind11::init<sdf::JointAxis>())
3940
.def("xyz", &sdf::JointAxis::Xyz,
4041
"Get the x,y,z components of the axis unit vector.")
41-
.def("set_xyz", &sdf::JointAxis::SetXyz,
42+
.def("set_xyz", [](JointAxis &self, const gz::math::Vector3d &_xyz)
43+
{
44+
ThrowIfErrors(self.SetXyz(_xyz));
45+
},
4246
"Set the x,y,z components of the axis unit vector.")
4347
.def("damping", &sdf::JointAxis::Damping,
4448
"Get the physical velocity dependent viscous damping coefficient "
@@ -104,8 +108,12 @@ void defineJointAxis(pybind11::object module)
104108
"Set the name of the coordinate frame in which this joint axis's "
105109
"unit vector is expressed. An empty value implies the parent (joint) "
106110
"frame.")
107-
.def("resolve_xyz", &sdf::JointAxis::ResolveXyz,
108-
pybind11::arg("_xyz"),
111+
.def("resolve_xyz", [](const JointAxis &self, const std::string &_resolveTo)
112+
{
113+
gz::math::Vector3d xyz;
114+
ThrowIfErrors(self.ResolveXyz(xyz, _resolveTo));
115+
return xyz;
116+
},
109117
pybind11::arg("_resolveTo") = "",
110118
"Express xyz unit vector of this axis in the coordinates of "
111119
"another named frame.")

python/src/sdf/pyModel.cc

+6-1
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@
2424
#include "sdf/Link.hh"
2525
#include "sdf/Model.hh"
2626

27+
#include "pybind11_helpers.hh"
28+
2729
using namespace pybind11::literals;
2830

2931
namespace sdf
@@ -38,7 +40,10 @@ void defineModel(pybind11::object module)
3840
pybind11::class_<sdf::Model>(module, "Model")
3941
.def(pybind11::init<>())
4042
.def(pybind11::init<sdf::Model>())
41-
.def("validate_graphs", &sdf::Model::ValidateGraphs,
43+
.def("validate_graphs", [](const sdf::Model &self)
44+
{
45+
ThrowIfErrors(self.ValidateGraphs());
46+
},
4247
"Check that the FrameAttachedToGraph and PoseRelativeToGraph "
4348
"are valid.")
4449
.def("name", &sdf::Model::Name,

python/src/sdf/pyRoot.cc

+26-10
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "sdf/Model.hh"
2424
#include "sdf/Root.hh"
2525
#include "sdf/World.hh"
26+
#include "pybind11_helpers.hh"
2627

2728
using namespace pybind11::literals;
2829

@@ -38,23 +39,32 @@ void defineRoot(pybind11::object module)
3839
pybind11::class_<sdf::Root>(module, "Root")
3940
.def(pybind11::init<>())
4041
.def("load",
41-
pybind11::overload_cast<const std::string &>(&sdf::Root::Load),
42+
[](Root &self, const std::string &_filename)
43+
{
44+
ThrowIfErrors(self.Load(_filename));
45+
},
4246
"Parse the given SDF file, and generate objects based on types "
4347
"specified in the SDF file.")
4448
.def("load",
45-
pybind11::overload_cast<
46-
const std::string &, const ParserConfig &>(&sdf::Root::Load),
49+
[](Root &self, const std::string &_filename,
50+
const ParserConfig &_config)
51+
{
52+
ThrowIfErrors(self.Load(_filename, _config));
53+
},
4754
"Parse the given SDF file, and generate objects based on types "
4855
"specified in the SDF file.")
4956
.def("load_sdf_string",
50-
pybind11::overload_cast<const std::string &>(
51-
&sdf::Root::LoadSdfString),
57+
[](Root &self, const std::string &_sdf)
58+
{
59+
ThrowIfErrors(self.LoadSdfString(_sdf));
60+
},
5261
"Parse the given SDF string, and generate objects based on types "
5362
"specified in the SDF file.")
5463
.def("load_sdf_string",
55-
pybind11::overload_cast<
56-
const std::string &, const ParserConfig &>(
57-
&sdf::Root::LoadSdfString),
64+
[](Root &self, const std::string &_sdf, const ParserConfig &_config)
65+
{
66+
ThrowIfErrors(self.LoadSdfString(_sdf, _config));
67+
},
5868
"Parse the given SDF string, and generate objects based on types "
5969
"specified in the SDF file.")
6070
.def("version", &sdf::Root::Version,
@@ -84,11 +94,17 @@ void defineRoot(pybind11::object module)
8494
.def("set_light", &sdf::Root::SetLight,
8595
"Set the light object. This will override any existing model, "
8696
"actor, and light object.")
87-
.def("add_world", &sdf::Root::AddWorld,
97+
.def("add_world", [](Root &self, const World &_world)
98+
{
99+
ThrowIfErrors(self.AddWorld(_world));
100+
},
88101
"Add a world to the root.")
89102
.def("clear_worlds", &sdf::Root::ClearWorlds,
90103
"Remove all worlds.")
91-
.def("update_graphs", &sdf::Root::UpdateGraphs,
104+
.def("update_graphs", [](Root &self)
105+
{
106+
ThrowIfErrors(self.UpdateGraphs());
107+
},
92108
"Recreate the frame and pose graphs for the worlds and model "
93109
"that are children of this Root object. You can call this function "
94110
"to build new graphs when the DOM was created programmatically, or "

python/src/sdf/pySemanticPose.cc

+8-2
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <gz/math/Pose3.hh>
2222

2323
#include "sdf/SemanticPose.hh"
24+
#include "pybind11_helpers.hh"
2425

2526
using namespace pybind11::literals;
2627

@@ -41,8 +42,13 @@ void defineSemanticPose(pybind11::object module)
4142
"Get the name of the coordinate frame relative to which this "
4243
"object's pose is expressed. An empty value indicates that the frame "
4344
"is relative to the default parent object.")
44-
.def("resolve", &sdf::SemanticPose::Resolve,
45-
pybind11::arg("_pose"),
45+
.def("resolve",
46+
[](const sdf::SemanticPose &self, const std::string &_resolveTo)
47+
{
48+
gz::math::Pose3d pose;
49+
ThrowIfErrors(self.Resolve(pose, _resolveTo));
50+
return pose;
51+
},
4652
pybind11::arg("_resolveTo") = "",
4753
"Resolve pose of this object with respect to another named frame. "
4854
"If there are any errors resolving the pose, the output will not be "

python/src/sdf/pybind11_helpers.cc

+38
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
/*
2+
* Copyright 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#include "pybind11_helpers.hh"
19+
20+
namespace sdf
21+
{
22+
// Inline bracket to help doxygen filtering.
23+
inline namespace SDF_VERSION_NAMESPACE
24+
{
25+
namespace python
26+
{
27+
/////////////////////////////////////////////////
28+
void ThrowIfErrors(const sdf::Errors &_errors)
29+
{
30+
if (!_errors.empty())
31+
{
32+
throw PySDFErrorsException(_errors);
33+
}
34+
}
35+
} // namespace python
36+
} // namespace SDF_VERSION_NAMESPACE
37+
} // namespace sdf
38+

python/src/sdf/pybind11_helpers.hh

+37
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
/*
2+
* Copyright 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#include <sdf/sdf_config.h>
19+
20+
#include <sdf/Types.hh>
21+
22+
#include "pyExceptions.hh"
23+
24+
namespace sdf
25+
{
26+
// Inline bracket to help doxygen filtering.
27+
inline namespace SDF_VERSION_NAMESPACE
28+
{
29+
namespace python
30+
{
31+
/// \brief Throw an exception if the `_errors` container is not empty.
32+
/// \param[in] _errors The list of errors to check.
33+
/// \throws PySDFErrorsException
34+
void ThrowIfErrors(const sdf::Errors &_errors);
35+
} // namespace python
36+
} // namespace SDF_VERSION_NAMESPACE
37+
} // namespace sdf

python/test/pyCollision_TEST.py

+5-6
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
import copy
1616
from ignition.math import Pose3d
1717
from sdformat import (Box, Collision, Contact, Cylinder, Error, Geometry,
18-
Plane, Surface, Sphere)
18+
Plane, Surface, Sphere, SDFErrorsException)
1919
import sdformat as sdf
2020
import unittest
2121
import math
@@ -35,10 +35,9 @@ def test_default_construction(self):
3535
semanticPose = collision.semantic_pose()
3636
self.assertEqual(collision.raw_pose(), semanticPose.raw_pose())
3737
self.assertTrue(not semanticPose.relative_to())
38-
pose = Pose3d()
3938
# expect errors when trying to resolve pose
40-
semanticPose.resolve(pose)
41-
# self.assertFalse()
39+
with self.assertRaises(SDFErrorsException):
40+
semanticPose.resolve()
4241

4342
collision.set_raw_pose(Pose3d(-10, -20, -30, math.pi, math.pi, math.pi))
4443
self.assertEqual(Pose3d(-10, -20, -30, math.pi, math.pi, math.pi),
@@ -50,9 +49,9 @@ def test_default_construction(self):
5049
semanticPose = collision.semantic_pose()
5150
self.assertEqual(collision.raw_pose(), semanticPose.raw_pose())
5251
self.assertEqual("link", semanticPose.relative_to())
53-
pose = Pose3d()
5452
# expect errors when trying to resolve pose
55-
# self.assertFalse(semanticPose.resolve(pose).empty())
53+
with self.assertRaises(SDFErrorsException):
54+
semanticPose.resolve()
5655

5756
self.assertNotEqual(None, collision.geometry())
5857
self.assertEqual(sdf.GeometryType.EMPTY, collision.geometry().type())

python/test/pyFrame_TEST.py

+6-6
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ def test_default_construction(self):
3434
semanticPose = frame.semantic_pose()
3535
self.assertEqual(Pose3d.ZERO, semanticPose.raw_pose())
3636
self.assertFalse(semanticPose.relative_to())
37-
pose = Pose3d()
3837
# expect errors when trying to resolve pose
39-
self.assertTrue(semanticPose.resolve(pose))
38+
with self.assertRaises(SDFErrorsException):
39+
semanticPose.resolve()
4040

4141
frame.set_attached_to("attachment")
4242
self.assertEqual("attachment", frame.attached_to())
@@ -48,19 +48,19 @@ def test_default_construction(self):
4848
semanticPose = frame.semantic_pose()
4949
self.assertEqual(frame.raw_pose(), semanticPose.raw_pose())
5050
self.assertEqual("attachment", semanticPose.relative_to())
51-
pose = Pose3d()
5251
# expect errors when trying to resolve pose
53-
self.assertTrue(semanticPose.resolve(pose))
52+
with self.assertRaises(SDFErrorsException):
53+
semanticPose.resolve()
5454

5555
frame.set_pose_relative_to("link")
5656
self.assertEqual("link", frame.pose_relative_to())
5757

5858
semanticPose = frame.semantic_pose()
5959
self.assertEqual(frame.raw_pose(), semanticPose.raw_pose())
6060
self.assertEqual("link", semanticPose.relative_to())
61-
pose = Pose3d()
6261
# expect errors when trying to resolve pose
63-
self.assertEqual(1, len(semanticPose.resolve(pose)))
62+
with self.assertRaises(SDFErrorsException):
63+
semanticPose.resolve()
6464

6565
with self.assertRaises(SDFErrorsException) as cm:
6666
resolveAttachedToBody = frame.resolve_attached_to_body()

0 commit comments

Comments
 (0)