From 2bc2d9063607658c76ee7867fc057ab47a765df0 Mon Sep 17 00:00:00 2001 From: Valenza Florian <fvalenza@laas.fr> Date: Wed, 13 Jul 2016 12:59:18 +0200 Subject: [PATCH] [C++] Removed type from GeometryObject. Still using the enum GeometryType to specify if visuals or collisions must be parsed from urdf file --- src/multibody/geometry.hpp | 26 ++++++++++---------------- src/multibody/geometry.hxx | 10 ++-------- src/parsers/urdf/geometry.hxx | 4 ++-- unittest/geom.cpp | 4 ++-- 4 files changed, 16 insertions(+), 28 deletions(-) diff --git a/src/multibody/geometry.hpp b/src/multibody/geometry.hpp index ec442535b..96ae0df8a 100644 --- a/src/multibody/geometry.hpp +++ b/src/multibody/geometry.hpp @@ -177,8 +177,6 @@ struct GeometryObject typedef Model::JointIndex JointIndex; typedef Model::GeomIndex GeomIndex; - /// \brief Type of the GeometryObject. Cann be VISUAL, COLLISION, or NONE (cf GeometryType enumeration) - GeometryType type; /// \brief Name of the geometry object std::string name; @@ -196,10 +194,9 @@ struct GeometryObject std::string mesh_path; - GeometryObject(const GeometryType type, const std::string & name, const JointIndex parent, const fcl::CollisionObject & collision, + GeometryObject(const std::string & name, const JointIndex parent, const fcl::CollisionObject & collision, const SE3 & placement, const std::string & mesh_path) - : type(type) - , name(name) + : name(name) , parent(parent) , collision_object(collision) , placement(placement) @@ -208,7 +205,6 @@ struct GeometryObject GeometryObject & operator=(const GeometryObject & other) { - type = other.type; name = other.name; parent = other.parent; collision_object = other.collision_object; @@ -221,18 +217,17 @@ struct GeometryObject inline bool operator==(const GeometryObject & lhs, const GeometryObject & rhs) { - return (lhs.type == rhs.type && lhs.name == rhs.name - && lhs.parent == rhs.parent - && lhs.collision_object == rhs.collision_object - && lhs.placement == rhs.placement - && lhs.mesh_path == rhs.mesh_path - ); + return ( lhs.name == rhs.name + && lhs.parent == rhs.parent + && lhs.collision_object == rhs.collision_object + && lhs.placement == rhs.placement + && lhs.mesh_path == rhs.mesh_path + ); } inline std::ostream & operator<< (std::ostream & os, const GeometryObject & geom_object) { - os << "Type: \t \n" << geom_object.type << "\n" - << "Name: \t \n" << geom_object.name << "\n" + os << "Name: \t \n" << geom_object.name << "\n" << "Parent ID: \t \n" << geom_object.parent << "\n" // << "collision object: \t \n" << geom_object.collision_object << "\n" << "Position in parent frame: \t \n" << geom_object.placement << "\n" @@ -284,13 +279,12 @@ struct GeometryObject * @param[in] placement The relative placement regarding to the parent frame * @param[in] geom_name The name of the Geometry Object * @param[in] mesh_path The absolute path to the mesh - * @param[in] type The type of the GeometryObject * * @return The index of the new added GeometryObject in geometry_objects */ inline GeomIndex addGeometryObject(const JointIndex parent, const fcl::CollisionObject & co, const SE3 & placement, const std::string & geom_name = "", - const std::string & mesh_path = "", const GeometryType type = NONE) throw(std::invalid_argument); + const std::string & mesh_path = "") throw(std::invalid_argument); diff --git a/src/multibody/geometry.hxx b/src/multibody/geometry.hxx index d4012904a..074aa088f 100644 --- a/src/multibody/geometry.hxx +++ b/src/multibody/geometry.hxx @@ -46,18 +46,12 @@ namespace se3 const fcl::CollisionObject & co, const SE3 & placement, const std::string & geom_name, - const std::string & mesh_path, - const GeometryType type) throw(std::invalid_argument) + const std::string & mesh_path) throw(std::invalid_argument) { - if (type == NONE) - { - const std::string exception_message ("You must specify if the geometryobject you want to add is of type VISUAL or COLLISION"); - throw std::invalid_argument(exception_message); - } Index idx = (Index) (ngeoms ++); - geometry_objects.push_back(GeometryObject(type, geom_name, parent, co, + geometry_objects.push_back(GeometryObject( geom_name, parent, co, placement, mesh_path)); addInnerObject(parent, idx); return idx; diff --git a/src/parsers/urdf/geometry.hxx b/src/parsers/urdf/geometry.hxx index 2b08e98d6..90130f921 100644 --- a/src/parsers/urdf/geometry.hxx +++ b/src/parsers/urdf/geometry.hxx @@ -165,7 +165,7 @@ namespace se3 fcl::CollisionObject collision_object = retrieveCollisionGeometry((*i)->geometry, package_dirs, mesh_path); SE3 geomPlacement = convertFromUrdf((*i)->origin); const std::string & collision_object_name = link_name; - geom_model.addGeometryObject(model.getFrameParent(link_name), collision_object, geomPlacement, collision_object_name, mesh_path, COLLISION); + geom_model.addGeometryObject(model.getFrameParent(link_name), collision_object, geomPlacement, collision_object_name, mesh_path); } } // if(link->collision) break; @@ -184,7 +184,7 @@ namespace se3 fcl::CollisionObject visual_object = retrieveCollisionGeometry((*i)->geometry, package_dirs, mesh_path); SE3 geomPlacement = convertFromUrdf((*i)->origin); const std::string & visual_object_name = link_name; - geom_model.addGeometryObject(model.getFrameParent(link_name), visual_object, geomPlacement, visual_object_name, mesh_path, VISUAL); + geom_model.addGeometryObject(model.getFrameParent(link_name), visual_object, geomPlacement, visual_object_name, mesh_path); } } // if(link->visual) break; diff --git a/unittest/geom.cpp b/unittest/geom.cpp index 9198405e0..fc5e4623b 100644 --- a/unittest/geom.cpp +++ b/unittest/geom.cpp @@ -155,11 +155,11 @@ BOOST_AUTO_TEST_CASE ( simple_boxes ) boost::shared_ptr<fcl::Box> Sample(new fcl::Box(1)); fcl::CollisionObject box1(Sample, fcl::Transform3f()); - model_geom.addGeometryObject(model.getJointId("planar1_joint"),box1, SE3::Identity(), "ff1_collision_object", "", COLLISION); + model_geom.addGeometryObject(model.getJointId("planar1_joint"),box1, SE3::Identity(), "ff1_collision_object", ""); boost::shared_ptr<fcl::Box> Sample2(new fcl::Box(1)); fcl::CollisionObject box2(Sample, fcl::Transform3f()); - model_geom.addGeometryObject(model.getJointId("planar2_joint"),box2, SE3::Identity(), "ff2_collision_object", "", COLLISION); + model_geom.addGeometryObject(model.getJointId("planar2_joint"),box2, SE3::Identity(), "ff2_collision_object", ""); se3::Data data(model); se3::GeometryData data_geom(data, model_geom); -- GitLab