Skip to content

Commit

Permalink
Added Frustum pybind11 interface (#353)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Dec 29, 2021
1 parent b148af5 commit 8ec7478
Show file tree
Hide file tree
Showing 6 changed files with 245 additions and 84 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ if (PYTHONLIBS_FOUND)
if (BUILD_TESTING)
# Add the Python tests
set(python_tests
Frustum_TEST
python_TEST
SignalStats_TEST
Sphere_TEST
Expand Down
2 changes: 2 additions & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ if (${pybind11_FOUND})
src/AxisAlignedBox.cc
src/Color.cc
src/DiffDriveOdometry.cc
src/Frustum.cc
src/GaussMarkovProcess.cc
src/Helpers.cc
src/Kmeans.cc
Expand Down Expand Up @@ -89,6 +90,7 @@ if (${pybind11_FOUND})
Cylinder_TEST
DiffDriveOdometry_TEST
Filter_TEST
Frustum_TEST
GaussMarkovProcess_TEST
Helpers_TEST
Inertial_TEST
Expand Down
115 changes: 115 additions & 0 deletions src/python_pybind11/src/Frustum.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <string>

#include "Frustum.hh"
#include <ignition/math/Frustum.hh>

#include <pybind11/operators.h>
#include <pybind11/stl_bind.h>

namespace ignition
{
namespace math
{
namespace python
{
void defineMathFrustum(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Frustum;
std::string pyclass_name = typestr;
py::class_<Class> (m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<const double, const double, const ignition::math::Angle&,
const double, const ignition::math::Pose3d&>(),
py::arg("_near") = 0,
py::arg("_far") = 0,
py::arg("_fov") = ignition::math::Angle(0),
py::arg("_aspectRatio") = 0,
py::arg("_pose") = ignition::math::Pose3d::Zero)
.def(py::init<const Class&>())
.def("near",
&Class::Near,
"Get the near distance. This is the distance from the "
"frustum's vertex to the closest plane.")
.def("set_near",
&Class::SetNear,
"Set the near distance. This is the distance from the "
"frustum's vertex to the closest plane.")
.def("far",
&Class::Far,
"Get the far distance. This is the distance from the "
"frustum's vertex to the farthest plane.")
.def("set_far",
&Class::SetFar,
"Set the far distance. This is the distance from the "
"frustum's vertex to the farthest plane.")
.def("fov",
&Class::FOV,
"Get the horizontal field of view. The field of view is the "
"angle between the frustum's vertex and the edges of the near or far")
.def("set_fov",
&Class::SetFOV,
"Set the horizontal field of view. The field of view is the "
"angle between the frustum's vertex and the edges of the near or far")
.def("aspect_ratio",
&Class::AspectRatio,
"Get the aspect ratio, which is the width divided by height "
"of the near or far planes.")
.def("set_aspect_ratio",
&Class::SetAspectRatio,
"Get the aspect ratio, which is the width divided by height "
"of the near or far planes.")
.def("pose",
&Class::Pose,
"Get the pose of the frustum")
.def("set_pose",
&Class::SetPose,
"Set the pose of the frustum")
.def("contains",
py::overload_cast<const ignition::math::AxisAlignedBox&>
(&Class::Contains, py::const_),
"Check if a box lies inside the pyramid frustum.")
.def("contains",
py::overload_cast<const ignition::math::Vector3d&>
(&Class::Contains, py::const_),
"Check if a point lies inside the pyramid frustum.")
.def("plane",
&Class::Plane,
"Get a plane of the frustum.");

py::enum_<ignition::math::Frustum::FrustumPlane>(m, "FrustumPlane")
.value("FRUSTUM_PLANE_NEAR",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_NEAR)
.value("FRUSTUM_PLANE_FAR",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_FAR)
.value("FRUSTUM_PLANE_LEFT",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_LEFT)
.value("FRUSTUM_PLANE_RIGHT",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_RIGHT)
.value("FRUSTUM_PLANE_TOP",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_TOP)
.value("FRUSTUM_PLANE_BOTTOM",
ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_BOTTOM)
.export_values();
}
} // namespace python
} // namespace math
} // namespace ignition
42 changes: 42 additions & 0 deletions src/python_pybind11/src/Frustum.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef IGNITION_MATH_PYTHON__FRUSTUM_HH_
#define IGNITION_MATH_PYTHON__FRUSTUM_HH_

#include <pybind11/pybind11.h>
#include <string>

namespace py = pybind11;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Frustum
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathFrustum(py::module &m, const std::string &typestr);
} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__FRUSTUM_HH_
3 changes: 3 additions & 0 deletions src/python_pybind11/src/_ignition_math_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "Cylinder.hh"
#include "DiffDriveOdometry.hh"
#include "Filter.hh"
#include "Frustum.hh"
#include "GaussMarkovProcess.hh"
#include "Helpers.hh"
#include "Inertial.hh"
Expand Down Expand Up @@ -155,6 +156,8 @@ PYBIND11_MODULE(math, m)

ignition::math::python::defineMathInertial<double>(m, "Inertiald");

ignition::math::python::defineMathFrustum(m, "Frustum");

ignition::math::python::defineMathFilter<int>(m, "Filteri");
ignition::math::python::defineMathFilter<float>(m, "Filterf");
ignition::math::python::defineMathFilter<double>(m, "Filterd");
Expand Down
Loading

0 comments on commit 8ec7478

Please sign in to comment.