Commit 56c651c7 authored by Jordan Lack's avatar Jordan Lack

move ptr typedefs to a types.hpp file

parent 7ea3f207
......@@ -16,6 +16,7 @@
#include "rdl_dynamics/SpatialForce.hpp"
#include "rdl_dynamics/rdl_mathutils.h"
#include "rdl_dynamics/types.hpp"
namespace RobotDynamics
{
......
......@@ -246,8 +246,6 @@ class FrameVector : public FrameObject, public Math::Vector3d
}
};
typedef std::shared_ptr<FrameVector> FrameVectorPtr;
inline FrameVector operator+(FrameVector v1, const Vector3d v2)
{
v1 += v2;
......
......@@ -19,6 +19,7 @@
#include <iostream>
#include "rdl_dynamics/FrameVectorPair.hpp"
#include "rdl_dynamics/Model.h"
#include "rdl_dynamics/types.hpp"
namespace RobotDynamics
{
......
......@@ -15,22 +15,21 @@
* @file Model.h
*/
#include "rdl_dynamics/rdl_math.hpp"
#include <map>
#include <memory>
#include <list>
#include <assert.h>
#include <iostream>
#include <limits>
#include <cstring>
#include <type_traits>
#include "rdl_dynamics/Joint.h"
#include "rdl_dynamics/Body.h"
#include "rdl_dynamics/SpatialAlgebraOperators.h"
#include "rdl_dynamics/Quaternion.h"
#include "rdl_dynamics/rdl_math.hpp"
#include "rdl_dynamics/RdlExceptions.hpp"
#include <type_traits>
#include "rdl_dynamics/types.hpp"
// std::vectors containing any objects that have Eigen matrices or vectors
// as members need to have a special allocater. This can be achieved with
......@@ -663,8 +662,6 @@ struct Model
return true;
}
};
typedef std::shared_ptr<Model> RdlModelPtr;
/** @} */
} // namespace RobotDynamics
......
......@@ -12,13 +12,15 @@
* @file ReferenceFrame.hpp
*/
#include <climits>
#include <memory>
#include "rdl_dynamics/SpatialAlgebraOperators.h"
#include <string>
#include <climits>
#include <utility>
#include <vector>
#include "rdl_dynamics/FrameExceptions.hpp"
#include "rdl_dynamics/SpatialAlgebraOperators.h"
#include "rdl_dynamics/types.hpp"
namespace RobotDynamics
{
......@@ -69,7 +71,6 @@ namespace RobotDynamics
class ReferenceFrame;
class FixedReferenceFrame;
typedef std::shared_ptr<ReferenceFrame> ReferenceFramePtr;
/**
* @class ReferenceFrame
......@@ -82,7 +83,7 @@ typedef std::shared_ptr<ReferenceFrame> ReferenceFramePtr;
* This class and its implementation are an adaptation of ReferenceFrame.java by <a href="http://robots.ihmc.us/">Jerry
**Pratt and the IHMC Robotics Group</a>.
*/
class ReferenceFrame : public std::enable_shared_from_this<ReferenceFrame>
class ReferenceFrame
{
public:
/**
......@@ -140,11 +141,6 @@ class ReferenceFrame : public std::enable_shared_from_this<ReferenceFrame>
update();
}
ReferenceFramePtr getPtr()
{
return shared_from_this();
}
/**
* @brief Empty constructor. All contained ptrs will be initialize to nullptr
*/
......
///*
// * RDL - Robot Dynamics Library
// * Copyright (c) 2019 Jordan Lack <jlack1987@gmail.com>
// *
// * Licensed under the zlib license. See LICENSE for more details.
// */
//
//#ifndef __RDL_TYPES_HPP__
//#define __RDL_TYPES_HPP__
//
//#include <memory>
//
// #define URDF_TYPEDEF_CLASS_POINTER(Class) \
//class Class; \
//typedef std::shared_ptr<Class> Class##SharedPtr; \
//typedef std::shared_ptr<const Class> Class##ConstSharedPtr; \
//typedef std::weak_ptr<Class> Class##WeakPtr
//
// namespace urdf{
//
//// shared pointer used in joint.h
// typedef std::shared_ptr<double> DoubleSharedPtr;
//
// URDF_TYPEDEF_CLASS_POINTER(Box);
// URDF_TYPEDEF_CLASS_POINTER(Collision);
// URDF_TYPEDEF_CLASS_POINTER(Cylinder);
// URDF_TYPEDEF_CLASS_POINTER(Geometry);
// URDF_TYPEDEF_CLASS_POINTER(Inertial);
// URDF_TYPEDEF_CLASS_POINTER(Joint);
// URDF_TYPEDEF_CLASS_POINTER(JointCalibration);
// URDF_TYPEDEF_CLASS_POINTER(JointDynamics);
// URDF_TYPEDEF_CLASS_POINTER(JointLimits);
// URDF_TYPEDEF_CLASS_POINTER(JointMimic);
// URDF_TYPEDEF_CLASS_POINTER(JointSafety);
// URDF_TYPEDEF_CLASS_POINTER(Link);
// URDF_TYPEDEF_CLASS_POINTER(Material);
// URDF_TYPEDEF_CLASS_POINTER(Mesh);
// URDF_TYPEDEF_CLASS_POINTER(Sphere);
// URDF_TYPEDEF_CLASS_POINTER(Visual);
//
//// create *_pointer_cast functions in urdf namespace
// template<class T, class U>
// std::shared_ptr<T> const_pointer_cast(std::shared_ptr<U> const & r)
// {
// return std::const_pointer_cast<T>(r);
// }
//
// template<class T, class U>
// std::shared_ptr<T> dynamic_pointer_cast(std::shared_ptr<U> const & r)
// {
// return std::dynamic_pointer_cast<T>(r);
// }
//
// template<class T, class U>
// std::shared_ptr<T> static_pointer_cast(std::shared_ptr<U> const & r)
// {
// return std::static_pointer_cast<T>(r);
// }
//
//}
//
//#endif
\ No newline at end of file
/*
* RDL - Robot Dynamics Library
* Copyright (c) 2019 Jordan Lack <jlack1987@gmail.com>
*
* Licensed under the zlib license. See LICENSE for more details.
*/
#ifndef __RDL_TYPES_HPP__
#define __RDL_TYPES_HPP__
#include <memory>
#define URDF_TYPEDEF_CLASS_POINTER(Class) \
class Class; \
typedef std::shared_ptr<Class> Class##Ptr; \
typedef std::shared_ptr<const Class> Class##ConstPtr; \
typedef std::weak_ptr<Class> Class##WeakPtr
namespace RobotDynamics{
URDF_TYPEDEF_CLASS_POINTER(Model);
URDF_TYPEDEF_CLASS_POINTER(ReferenceFrame);
}
#endif
\ No newline at end of file
......@@ -11,7 +11,8 @@
#ifndef __RDL_URDFREADER_H__
#define __RDL_URDFREADER_H__
#include <rdl_dynamics/rdl_config.h>
#include "rdl_dynamics/rdl_config.h"
#include "rdl_dynamics/types.hpp"
namespace RobotDynamics
{
......@@ -26,7 +27,7 @@ namespace Urdf
* @param verbose
* @return
*/
bool urdfReadFromFile(const char* filename, Model* model, bool floating_base, bool verbose = false);
bool urdfReadFromFile(const char* filename, ModelPtr model, bool floating_base, bool verbose = false);
/**
* @brief Read urdf from file path
......@@ -36,7 +37,7 @@ bool urdfReadFromFile(const char* filename, Model* model, bool floating_base, bo
* @param verbose
* @return
*/
bool urdfReadFromFile(const std::string& filename, RdlModelPtr model);
bool urdfReadFromFile(const std::string& filename, ModelPtr model);
/**
* @brief Read urdf from string contents
......@@ -46,7 +47,7 @@ bool urdfReadFromFile(const std::string& filename, RdlModelPtr model);
* @param verbose
* @return
*/
bool urdfReadFromString(const char* model_xml_string, Model* model, bool floating_base, bool verbose = false);
bool urdfReadFromString(const char* model_xml_string, ModelPtr model, bool floating_base, bool verbose = false);
/**
* @brief Read urdf from string contents
......@@ -58,7 +59,7 @@ bool urdfReadFromString(const char* model_xml_string, Model* model, bool floatin
* @note This function will deduce whether or not the robot has a floating base by checking the name of
* the root link. If the name of the root link is "world", then it will have a floating base.
*/
bool urdfReadFromString(const std::string& model_xml_string, RdlModelPtr model);
bool urdfReadFromString(const std::string& model_xml_string, ModelPtr model);
/**
* @brief This will build a map of joint name to body name.
......
......@@ -61,9 +61,9 @@ int main(int argc, char *argv[])
}
}
RobotDynamics::Model model;
RobotDynamics::ModelPtr model(new RobotDynamics::Model());
if(!RobotDynamics::Urdf::urdfReadFromFile(filename.c_str(), &model, floatbase, verbose))
if(!RobotDynamics::Urdf::urdfReadFromFile(filename.c_str(), model, floatbase, verbose))
{
cerr << "Loading of urdf model failed!" << endl;
return -1;
......@@ -74,13 +74,13 @@ int main(int argc, char *argv[])
if(dof_overview)
{
cout << "Degree of freedom overview:" << endl;
cout << RobotDynamics::Utils::getModelDOFOverview(model);
cout << RobotDynamics::Utils::getModelDOFOverview(*model);
}
if(model_hierarchy)
{
cout << "Model Hierarchy:" << endl;
cout << RobotDynamics::Utils::getModelHierarchy(model);
cout << RobotDynamics::Utils::getModelHierarchy(*model);
}
return 0;
......
......@@ -22,7 +22,7 @@ namespace RobotDynamics
typedef map<string, urdf::LinkSharedPtr> URDFLinkMap;
typedef map<string, urdf::JointSharedPtr> URDFJointMap;
bool construct_model(Model *rdl_model, urdf::ModelInterfaceSharedPtr urdf_model, bool floating_base, bool verbose)
bool construct_model(ModelPtr rdl_model, urdf::ModelInterfaceSharedPtr urdf_model, bool floating_base, bool verbose)
{
urdf::LinkSharedPtr urdf_root_link;
......@@ -325,7 +325,7 @@ namespace RobotDynamics
return true;
}
bool urdfReadFromFile(const char *filename, Model *model, bool floating_base, bool verbose)
bool urdfReadFromFile(const char *filename, ModelPtr model, bool floating_base, bool verbose)
{
ifstream model_file(filename);
if(!model_file)
......@@ -346,7 +346,7 @@ namespace RobotDynamics
return urdfReadFromString(model_xml_string.c_str(), model, floating_base, verbose);
}
bool urdfReadFromString(const char *model_xml_string, Model *model, bool floating_base,
bool urdfReadFromString(const char *model_xml_string, ModelPtr model, bool floating_base,
bool verbose)
{
assert (model);
......@@ -364,7 +364,7 @@ namespace RobotDynamics
return true;
}
bool urdfReadFromFile(const std::string& filename, RdlModelPtr model)
bool urdfReadFromFile(const std::string& filename, ModelPtr model)
{
ifstream model_file(filename.c_str());
if(!model_file)
......@@ -385,7 +385,7 @@ namespace RobotDynamics
return urdfReadFromString(model_xml_string, model);
}
bool urdfReadFromString(const std::string& model_xml_string, RdlModelPtr model)
bool urdfReadFromString(const std::string& model_xml_string, ModelPtr model)
{
assert (model);
......@@ -393,7 +393,7 @@ namespace RobotDynamics
bool floating_base = std::strcmp(urdf_model->getRoot()->name.c_str(), "world") ? true : false;
if(!construct_model(model.get(), urdf_model, floating_base, false))
if(!construct_model(model, urdf_model, floating_base, false))
{
cerr << "Error constructing model from urdf file." << endl;
return false;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment