Code-style consistency improvement:

Apply clang-format-all.sh using the _clang-format file through all the cpp/.h files.
make sure not to apply it to certain serialization structures, since some parser expects the * as part of the name, instead of type.
This commit contains no other changes aside from adding and applying clang-format-all.sh
This commit is contained in:
erwincoumans
2018-09-23 14:17:31 -07:00
parent b73b05e9fb
commit ab8f16961e
1773 changed files with 1081087 additions and 474249 deletions

View File

@@ -12,14 +12,12 @@
struct ErrorLogger
{
virtual ~ErrorLogger(){}
virtual void reportError(const char* error)=0;
virtual void reportWarning(const char* warning)=0;
virtual void printMessage(const char* msg)=0;
virtual ~ErrorLogger() {}
virtual void reportError(const char* error) = 0;
virtual void reportWarning(const char* warning) = 0;
virtual void printMessage(const char* msg) = 0;
};
struct UrdfMaterial
{
std::string m_name;
@@ -37,38 +35,37 @@ struct UrdfInertia
bool m_hasLinkLocalFrame;
double m_mass;
double m_ixx,m_ixy,m_ixz,m_iyy,m_iyz,m_izz;
double m_ixx, m_ixy, m_ixz, m_iyy, m_iyz, m_izz;
UrdfInertia()
{
m_hasLinkLocalFrame = false;
m_linkLocalFrame.setIdentity();
m_mass = 0.f;
m_ixx=m_ixy=m_ixz=m_iyy=m_iyz=m_izz=0.f;
m_ixx = m_ixy = m_ixz = m_iyy = m_iyz = m_izz = 0.f;
}
};
enum UrdfGeomTypes
{
URDF_GEOM_SPHERE=2,
URDF_GEOM_SPHERE = 2,
URDF_GEOM_BOX,
URDF_GEOM_CYLINDER,
URDF_GEOM_MESH,
URDF_GEOM_PLANE,
URDF_GEOM_CAPSULE, //non-standard URDF
URDF_GEOM_CDF,//signed-distance-field, non-standard URDF
URDF_GEOM_UNKNOWN,
URDF_GEOM_CAPSULE, //non-standard URDF
URDF_GEOM_CDF, //signed-distance-field, non-standard URDF
URDF_GEOM_UNKNOWN,
};
struct UrdfGeometry
{
UrdfGeomTypes m_type;
double m_sphereRadius;
btVector3 m_boxSize;
double m_capsuleRadius;
double m_capsuleHeight;
int m_hasFromTo;
@@ -76,42 +73,42 @@ struct UrdfGeometry
btVector3 m_capsuleTo;
btVector3 m_planeNormal;
enum {
FILE_STL =1,
FILE_COLLADA =2,
FILE_OBJ =3,
enum
{
FILE_STL = 1,
FILE_COLLADA = 2,
FILE_OBJ = 3,
FILE_CDF = 4,
};
int m_meshFileType;
int m_meshFileType;
std::string m_meshFileName;
btVector3 m_meshScale;
btVector3 m_meshScale;
UrdfMaterial m_localMaterial;
bool m_hasLocalMaterial;
UrdfGeometry()
:m_type(URDF_GEOM_UNKNOWN),
m_sphereRadius(1),
m_boxSize(1,1,1),
m_capsuleRadius(1),
m_capsuleHeight(1),
m_hasFromTo(0),
m_capsuleFrom(0,1,0),
m_capsuleTo(1,0,0),
m_planeNormal(0,0,1),
m_meshFileType(0),
m_meshScale(1,1,1),
m_hasLocalMaterial(false)
: m_type(URDF_GEOM_UNKNOWN),
m_sphereRadius(1),
m_boxSize(1, 1, 1),
m_capsuleRadius(1),
m_capsuleHeight(1),
m_hasFromTo(0),
m_capsuleFrom(0, 1, 0),
m_capsuleTo(1, 0, 0),
m_planeNormal(0, 0, 1),
m_meshFileType(0),
m_meshScale(1, 1, 1),
m_hasLocalMaterial(false)
{
}
};
bool findExistingMeshFile(const std::string& urdf_path, std::string fn,
const std::string& error_message_prefix,
std::string* out_found_filename, int* out_type); // intended to fill UrdfGeometry::m_meshFileName and Type, but can be used elsewhere
const std::string& error_message_prefix,
std::string* out_found_filename, int* out_type); // intended to fill UrdfGeometry::m_meshFileName and Type, but can be used elsewhere
struct UrdfShape
{
@@ -121,18 +118,18 @@ struct UrdfShape
std::string m_name;
};
struct UrdfVisual: UrdfShape
struct UrdfVisual : UrdfShape
{
std::string m_materialName;
};
struct UrdfCollision: UrdfShape
struct UrdfCollision : UrdfShape
{
int m_flags;
int m_collisionGroup;
int m_collisionMask;
UrdfCollision()
:m_flags(0)
: m_flags(0)
{
}
};
@@ -141,30 +138,29 @@ struct UrdfJoint;
struct UrdfLink
{
std::string m_name;
UrdfInertia m_inertia;
btTransform m_linkTransformInWorld;
std::string m_name;
UrdfInertia m_inertia;
btTransform m_linkTransformInWorld;
btArray<UrdfVisual> m_visualArray;
btArray<UrdfCollision> m_collisionArray;
UrdfLink* m_parentLink;
UrdfJoint* m_parentJoint;
btArray<UrdfJoint*> m_childJoints;
btArray<UrdfLink*> m_childLinks;
int m_linkIndex;
URDFLinkContactInfo m_contactInfo;
SDFAudioSource m_audioSource;
UrdfLink()
:m_parentLink(0),
m_parentJoint(0),
m_linkIndex(-2)
: m_parentLink(0),
m_parentJoint(0),
m_linkIndex(-2)
{
}
};
struct UrdfJoint
{
@@ -174,22 +170,22 @@ struct UrdfJoint
std::string m_parentLinkName;
std::string m_childLinkName;
btVector3 m_localJointAxis;
double m_lowerLimit;
double m_upperLimit;
double m_effortLimit;
double m_velocityLimit;
double m_jointDamping;
double m_jointFriction;
UrdfJoint()
:m_lowerLimit(0),
m_upperLimit(-1),
m_effortLimit(0),
m_velocityLimit(0),
m_jointDamping(0),
m_jointFriction(0)
: m_lowerLimit(0),
m_upperLimit(-1),
m_effortLimit(0),
m_velocityLimit(0),
m_jointDamping(0),
m_jointFriction(0)
{
}
};
@@ -198,16 +194,16 @@ struct UrdfModel
{
std::string m_name;
std::string m_sourceFile;
btTransform m_rootTransformInWorld;
btTransform m_rootTransformInWorld;
btHashMap<btHashString, UrdfMaterial*> m_materials;
btHashMap<btHashString, UrdfLink*> m_links;
btHashMap<btHashString, UrdfJoint*> m_joints;
btArray<UrdfLink*> m_rootLinks;
bool m_overrideFixedBase;
UrdfModel()
:m_overrideFixedBase(false)
: m_overrideFixedBase(false)
{
m_rootTransformInWorld.setIdentity();
}
@@ -246,99 +242,96 @@ struct UrdfModel
namespace tinyxml2
{
class XMLElement;
class XMLElement;
};
class UrdfParser
{
protected:
UrdfModel m_urdf2Model;
btAlignedObjectArray<UrdfModel*> m_sdfModels;
btAlignedObjectArray<UrdfModel*> m_tmpModels;
bool m_parseSDF;
int m_activeSdfModel;
UrdfModel m_urdf2Model;
btAlignedObjectArray<UrdfModel*> m_sdfModels;
btAlignedObjectArray<UrdfModel*> m_tmpModels;
bool m_parseSDF;
int m_activeSdfModel;
btScalar m_urdfScaling;
bool parseTransform(btTransform& tr, tinyxml2::XMLElement* xml, ErrorLogger* logger, bool parseSDF = false);
bool parseTransform(btTransform& tr, tinyxml2::XMLElement* xml, ErrorLogger* logger, bool parseSDF = false);
bool parseInertia(UrdfInertia& inertia, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseGeometry(UrdfGeometry& geom, tinyxml2::XMLElement* g, ErrorLogger* logger);
bool parseVisual(UrdfModel& model, UrdfVisual& visual, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseCollision(UrdfCollision& collision, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool initTreeAndRoot(UrdfModel& model, ErrorLogger* logger);
bool parseMaterial(UrdfMaterial& material, tinyxml2::XMLElement *config, ErrorLogger* logger);
bool parseMaterial(UrdfMaterial& material, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseJointLimits(UrdfJoint& joint, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseJointDynamics(UrdfJoint& joint, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseJoint(UrdfJoint& joint, tinyxml2::XMLElement *config, ErrorLogger* logger);
bool parseLink(UrdfModel& model, UrdfLink& link, tinyxml2::XMLElement *config, ErrorLogger* logger);
bool parseJointDynamics(UrdfJoint& joint, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseJoint(UrdfJoint& joint, tinyxml2::XMLElement* config, ErrorLogger* logger);
bool parseLink(UrdfModel& model, UrdfLink& link, tinyxml2::XMLElement* config, ErrorLogger* logger);
public:
UrdfParser();
virtual ~UrdfParser();
void setParseSDF(bool useSDF)
{
m_parseSDF = useSDF;
}
bool getParseSDF() const
{
return m_parseSDF;
}
void setParseSDF(bool useSDF)
{
m_parseSDF = useSDF;
}
bool getParseSDF() const
{
return m_parseSDF;
}
void setGlobalScaling(btScalar scaling)
{
m_urdfScaling = scaling;
}
bool loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceFixedBase);
bool loadSDF(const char* sdfText, ErrorLogger* logger);
int getNumModels() const
{
//user should have loaded an SDF when calling this method
if (m_parseSDF)
{
return m_sdfModels.size();
}
return 1;
}
void activateModel(int modelIndex);
UrdfModel& getModelByIndex(int index)
{
//user should have loaded an SDF when calling this method
btAssert(m_parseSDF);
bool loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceFixedBase);
bool loadSDF(const char* sdfText, ErrorLogger* logger);
return *m_sdfModels[index];
}
const UrdfModel& getModelByIndex(int index) const
{
//user should have loaded an SDF when calling this method
btAssert(m_parseSDF);
return *m_sdfModels[index];
}
const UrdfModel& getModel() const
int getNumModels() const
{
if (m_parseSDF)
{
return *m_sdfModels[m_activeSdfModel];
}
//user should have loaded an SDF when calling this method
if (m_parseSDF)
{
return m_sdfModels.size();
}
return 1;
}
void activateModel(int modelIndex);
UrdfModel& getModelByIndex(int index)
{
//user should have loaded an SDF when calling this method
btAssert(m_parseSDF);
return *m_sdfModels[index];
}
const UrdfModel& getModelByIndex(int index) const
{
//user should have loaded an SDF when calling this method
btAssert(m_parseSDF);
return *m_sdfModels[index];
}
const UrdfModel& getModel() const
{
if (m_parseSDF)
{
return *m_sdfModels[m_activeSdfModel];
}
return m_urdf2Model;
}
UrdfModel& getModel()
{
if (m_parseSDF)
{
return *m_sdfModels[m_activeSdfModel];
}
{
if (m_parseSDF)
{
return *m_sdfModels[m_activeSdfModel];
}
return m_urdf2Model;
}
@@ -351,4 +344,3 @@ public:
};
#endif