From b948c619ab8537d4ceea7f8f268bd0a5b7b72067 Mon Sep 17 00:00:00 2001 From: Gabriele Buondonno <gbuondon@laas.fr> Date: Sat, 2 Nov 2019 19:54:44 +0100 Subject: [PATCH] [python] Simplify Box bindings --- python/collision-geometries.cc | 15 +++------------ python/math.cc | 3 --- 2 files changed, 3 insertions(+), 15 deletions(-) diff --git a/python/collision-geometries.cc b/python/collision-geometries.cc index 7a57def1..7d3b63f9 100644 --- a/python/collision-geometries.cc +++ b/python/collision-geometries.cc @@ -103,17 +103,6 @@ struct ConvexWrapper } }; -Eigen::Vector3d getHalfSide(const ::hpp::fcl::Box & box) -{ - Eigen::Vector3d halfSide = box.halfSide; - return halfSide; -} - -void setHalfSide(::hpp::fcl::Box & box, const Eigen::Vector3d & halfSide) -{ - box.halfSide = halfSide; -} - void exposeShapes () { class_ <ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>, noncopyable> @@ -125,7 +114,9 @@ void exposeShapes () ("Box", init<>()) .def (init<FCL_REAL,FCL_REAL,FCL_REAL>()) .def (init<Vec3f>()) - .add_property("halfSide", make_function(getHalfSide), make_function(setHalfSide)) + .add_property("halfSide", + make_getter(&Box::halfSide, return_value_policy<return_by_value>()), + make_setter(&Box::halfSide, return_value_policy<return_by_value>())); ; class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> > diff --git a/python/math.cc b/python/math.cc index 2edaf360..0b47a345 100644 --- a/python/math.cc +++ b/python/math.cc @@ -69,9 +69,6 @@ void exposeMaths () if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>()) eigenpy::exposeAngleAxis(); - eigenpy::enableEigenPySpecific<Matrix3f>(); - eigenpy::enableEigenPySpecific<Vec3f >(); - class_ <Transform3f> ("Transform3f", init<>()) .def (init<Matrix3f, Vec3f>()) .def (init<Quaternion3f, Vec3f>()) -- GitLab