diff --git a/urdf_model/include/urdf_model/joint.h b/urdf_model/include/urdf_model/joint.h index c68a298..97b600b 100644 --- a/urdf_model/include/urdf_model/joint.h +++ b/urdf_model/include/urdf_model/joint.h @@ -39,9 +39,9 @@ #include #include -#include #include "urdf_model/pose.h" +#include "urdf_model/types.h" namespace urdf{ @@ -138,7 +138,7 @@ class JointCalibration public: JointCalibration() { this->clear(); }; double reference_position; - boost::shared_ptr rising, falling; + DoubleSharedPtr rising, falling; void clear() { @@ -196,19 +196,19 @@ class Joint Pose parent_to_joint_origin_transform; /// Joint Dynamics - boost::shared_ptr dynamics; + JointDynamicsSharedPtr dynamics; /// Joint Limits - boost::shared_ptr limits; + JointLimitsSharedPtr limits; /// Unsupported Hidden Feature - boost::shared_ptr safety; + JointSafetySharedPtr safety; /// Unsupported Hidden Feature - boost::shared_ptr calibration; + JointCalibrationSharedPtr calibration; /// Option to Mimic another Joint - boost::shared_ptr mimic; + JointMimicSharedPtr mimic; void clear() { diff --git a/urdf_model/include/urdf_model/link.h b/urdf_model/include/urdf_model/link.h index b45f7ae..e470b43 100644 --- a/urdf_model/include/urdf_model/link.h +++ b/urdf_model/include/urdf_model/link.h @@ -40,11 +40,10 @@ #include #include #include -#include -#include #include "joint.h" #include "color.h" +#include "types.h" namespace urdf{ @@ -150,10 +149,10 @@ class Visual public: Visual() { this->clear(); }; Pose origin; - boost::shared_ptr geometry; + GeometrySharedPtr geometry; std::string material_name; - boost::shared_ptr material; + MaterialSharedPtr material; void clear() { @@ -172,7 +171,7 @@ class Collision public: Collision() { this->clear(); }; Pose origin; - boost::shared_ptr geometry; + GeometrySharedPtr geometry; void clear() { @@ -194,32 +193,32 @@ class Link std::string name; /// inertial element - boost::shared_ptr inertial; + InertialSharedPtr inertial; /// visual element - boost::shared_ptr visual; + VisualSharedPtr visual; /// collision element - boost::shared_ptr collision; + CollisionSharedPtr collision; /// if more than one collision element is specified, all collision elements are placed in this array (the collision member points to the first element of the array) - std::vector > collision_array; + std::vector collision_array; /// if more than one visual element is specified, all visual elements are placed in this array (the visual member points to the first element of the array) - std::vector > visual_array; + std::vector visual_array; /// Parent Joint element /// explicitly stating "parent" because we want directional-ness for tree structure /// every link can have one parent - boost::shared_ptr parent_joint; + JointSharedPtr parent_joint; - std::vector > child_joints; - std::vector > child_links; + std::vector child_joints; + std::vector child_links; - boost::shared_ptr getParent() const + LinkSharedPtr getParent() const {return parent_link_.lock();}; - void setParent(const boost::shared_ptr &parent) + void setParent(const LinkSharedPtr &parent) { parent_link_ = parent; } void clear() @@ -236,7 +235,7 @@ class Link }; private: - boost::weak_ptr parent_link_; + LinkWeakPtr parent_link_; }; diff --git a/urdf_model/include/urdf_model/model.h b/urdf_model/include/urdf_model/model.h index bbccf2c..b7b2f96 100644 --- a/urdf_model/include/urdf_model/model.h +++ b/urdf_model/include/urdf_model/model.h @@ -41,6 +41,7 @@ #include #include #include +#include #include namespace urdf { @@ -48,10 +49,10 @@ namespace urdf { class ModelInterface { public: - boost::shared_ptr getRoot(void) const{return this->root_link_;}; - boost::shared_ptr getLink(const std::string& name) const + LinkConstSharedPtr getRoot(void) const{return this->root_link_;}; + LinkConstSharedPtr getLink(const std::string& name) const { - boost::shared_ptr ptr; + LinkConstSharedPtr ptr; if (this->links_.find(name) == this->links_.end()) ptr.reset(); else @@ -59,9 +60,9 @@ class ModelInterface return ptr; }; - boost::shared_ptr getJoint(const std::string& name) const + JointConstSharedPtr getJoint(const std::string& name) const { - boost::shared_ptr ptr; + JointConstSharedPtr ptr; if (this->joints_.find(name) == this->joints_.end()) ptr.reset(); else @@ -71,9 +72,9 @@ class ModelInterface const std::string& getName() const {return name_;}; - void getLinks(std::vector >& links) const + void getLinks(std::vector& links) const { - for (std::map >::const_iterator link = this->links_.begin();link != this->links_.end(); link++) + for (std::map::const_iterator link = this->links_.begin();link != this->links_.end(); link++) { links.push_back(link->second); } @@ -89,9 +90,9 @@ class ModelInterface }; /// non-const getLink() - void getLink(const std::string& name,boost::shared_ptr &link) const + void getLink(const std::string& name, LinkSharedPtr &link) const { - boost::shared_ptr ptr; + LinkSharedPtr ptr; if (this->links_.find(name) == this->links_.end()) ptr.reset(); else @@ -100,9 +101,9 @@ class ModelInterface }; /// non-const getMaterial() - boost::shared_ptr getMaterial(const std::string& name) const + MaterialSharedPtr getMaterial(const std::string& name) const { - boost::shared_ptr ptr; + MaterialSharedPtr ptr; if (this->materials_.find(name) == this->materials_.end()) ptr.reset(); else @@ -113,7 +114,7 @@ class ModelInterface void initTree(std::map &parent_link_tree) { // loop through all joints, for every link, assign children links and children joints - for (std::map >::iterator joint = this->joints_.begin();joint != this->joints_.end(); joint++) + for (std::map::iterator joint = this->joints_.begin();joint != this->joints_.end(); joint++) { std::string parent_link_name = joint->second->parent_link_name; std::string child_link_name = joint->second->child_link_name; @@ -125,7 +126,7 @@ class ModelInterface else { // find child and parent links - boost::shared_ptr child_link, parent_link; + LinkSharedPtr child_link, parent_link; this->getLink(child_link_name, child_link); if (!child_link) { @@ -160,7 +161,7 @@ class ModelInterface this->root_link_.reset(); // find the links that have no parent in the tree - for (std::map >::const_iterator l=this->links_.begin(); l!=this->links_.end(); l++) + for (std::map::const_iterator l=this->links_.begin(); l!=this->links_.end(); l++) { std::map::const_iterator parent = parent_link_tree.find(l->first); if (parent == parent_link_tree.end()) @@ -185,17 +186,17 @@ class ModelInterface /// \brief complete list of Links - std::map > links_; + std::map links_; /// \brief complete list of Joints - std::map > joints_; + std::map joints_; /// \brief complete list of Materials - std::map > materials_; + std::map materials_; /// \brief The name of the robot model std::string name_; /// \brief The root is always a link (the parent of the tree describing the robot) - boost::shared_ptr root_link_; + LinkSharedPtr root_link_; diff --git a/urdf_model_state/include/urdf_model_state/model_state.h b/urdf_model_state/include/urdf_model_state/model_state.h index b132719..a8c5263 100644 --- a/urdf_model_state/include/urdf_model_state/model_state.h +++ b/urdf_model_state/include/urdf_model_state/model_state.h @@ -40,11 +40,10 @@ #include #include #include -#include -#include #include "urdf_model/pose.h" #include +#include "urdf_model_state/types.h" namespace urdf{ @@ -131,7 +130,7 @@ class ModelState this->joint_states.clear(); }; - std::vector > joint_states; + std::vector joint_states; }; diff --git a/urdf_sensor/include/urdf_sensor/sensor.h b/urdf_sensor/include/urdf_sensor/sensor.h index 3b99695..c19fac1 100644 --- a/urdf_sensor/include/urdf_sensor/sensor.h +++ b/urdf_sensor/include/urdf_sensor/sensor.h @@ -69,6 +69,8 @@ #include "urdf_model/pose.h" #include "urdf_model/joint.h" #include "urdf_model/link.h" +#include "urdf_model/types.h" +#include "urdf_sensor/types.h" namespace urdf{ @@ -148,16 +150,16 @@ class Sensor Pose origin; /// sensor - boost::shared_ptr sensor; + VisualSensorSharedPtr sensor; /// Parent link element name. A pointer is stored in parent_link_. std::string parent_link_name; - boost::shared_ptr getParent() const + LinkSharedPtr getParent() const {return parent_link_.lock();}; - void setParent(boost::shared_ptr parent) + void setParent(LinkSharedPtr parent) { this->parent_link_ = parent; } void clear() @@ -169,7 +171,7 @@ class Sensor }; private: - boost::weak_ptr parent_link_; + LinkWeakPtr parent_link_; }; } diff --git a/urdf_world/include/urdf_world/world.h b/urdf_world/include/urdf_world/world.h index 1d3f000..7b0e8c1 100644 --- a/urdf_world/include/urdf_world/world.h +++ b/urdf_world/include/urdf_world/world.h @@ -74,19 +74,18 @@ #include #include #include -#include -#include #include "urdf_model/model.h" #include "urdf_model/pose.h" #include "urdf_model/twist.h" +#include "urdf_world/types.h" namespace urdf{ class Entity { public: - boost::shared_ptr model; + ModelInterfaceSharedPtr model; Pose origin; Twist twist; };