|
From: <is...@us...> - 2008-07-18 00:08:33
|
Revision: 1737
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1737&view=rev
Author: isucan
Date: 2008-07-18 00:08:36 +0000 (Fri, 18 Jul 2008)
Log Message:
-----------
added namespace for robot models
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/util/collision_space/include/collision_space/environment.h
pkg/trunk/util/collision_space/include/collision_space/environmentODE.h
pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/util/collision_space/src/test/test_kinematic_ode.cpp
pkg/trunk/util/robot_models/include/robot_models/kinematic.h
pkg/trunk/util/robot_models/src/robot_models/kinematic.cpp
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-18 00:08:36 UTC (rev 1737)
@@ -163,7 +163,6 @@
{
ompl::SpaceInformationKinematic_t si;
ompl::MotionPlanner_t mp;
- // collision space
};
std::vector<Model> models;
Modified: pkg/trunk/util/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/util/collision_space/include/collision_space/environment.h 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/collision_space/include/collision_space/environment.h 2008-07-18 00:08:36 UTC (rev 1737)
@@ -60,7 +60,7 @@
/** Add a point cloud to the collision space */
virtual void addPointCloud(unsigned int n, const double* points, double radius = 0.01) = 0;
- KinematicModel *model;
+ robot_models::KinematicModel *model;
};
Modified: pkg/trunk/util/collision_space/include/collision_space/environmentODE.h
===================================================================
--- pkg/trunk/util/collision_space/include/collision_space/environmentODE.h 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/collision_space/include/collision_space/environmentODE.h 2008-07-18 00:08:36 UTC (rev 1737)
@@ -46,7 +46,7 @@
{
public:
- class KinematicModelODE : public KinematicModel
+ class KinematicModelODE : public robot_models::KinematicModel
{
public:
@@ -92,7 +92,7 @@
EnvironmentModelODE(void) : EnvironmentModel()
{
- model = dynamic_cast<KinematicModel*>(&m_modelODE);
+ model = dynamic_cast<robot_models::KinematicModel*>(&m_modelODE);
m_space = dHashSpaceCreate(0);
m_modelODE.setODESpace(m_space);
}
Modified: pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp 2008-07-18 00:08:36 UTC (rev 1737)
@@ -37,7 +37,7 @@
void EnvironmentModelODE::KinematicModelODE::build(URDF &model, const char *group)
{
- KinematicModel::build(model, group);
+ robot_models::KinematicModel::build(model, group);
assert(m_space);
for (unsigned int i = 0 ; i < m_robots.size() ; ++i)
buildODEGeoms(m_robots[i]);
Modified: pkg/trunk/util/collision_space/src/test/test_kinematic_ode.cpp
===================================================================
--- pkg/trunk/util/collision_space/src/test/test_kinematic_ode.cpp 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/collision_space/src/test/test_kinematic_ode.cpp 2008-07-18 00:08:36 UTC (rev 1737)
@@ -121,7 +121,7 @@
km.model->build(model);
printf("number of robots = %d\n", km.model->getRobotCount());
- KinematicModel::Robot *r = km.model->getRobot(0);
+ robot_models::KinematicModel::Robot *r = km.model->getRobot(0);
printf("state dimension = %d\n", r->stateDimension);
double *param = new double[r->stateDimension];
Modified: pkg/trunk/util/robot_models/include/robot_models/kinematic.h
===================================================================
--- pkg/trunk/util/robot_models/include/robot_models/kinematic.h 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/robot_models/include/robot_models/kinematic.h 2008-07-18 00:08:36 UTC (rev 1737)
@@ -44,186 +44,192 @@
A class describing a kinematic robot model loaded from URDF */
-class KinematicModel
+namespace robot_models
{
- public:
-
- /** Possible geometry elements. These are assumed to be centered at origin (similar to ODE) */
- struct Geometry
- {
- Geometry(void)
- {
- type = UNKNOWN;
- size[0] = size[1] = size[2] = 0.0;
- }
-
- enum
- {
- UNKNOWN, BOX, CYLINDER, SPHERE
- } type;
- double size[3];
- };
- struct Joint;
- struct Link;
-
- /** A joint from the robot. Contains the transform applied by the joint type */
- struct Joint
+ class KinematicModel
{
- Joint(void)
- {
- before = after = NULL;
- usedParamStart = usedParamEnd = 0;
- axis[0] = axis[1] = axis[2] = 0.0;
- anchor[0] = anchor[1] = anchor[2] = 0.0;
- limit[0] = limit[1] = 0.0;
- type = UNKNOWN;
- }
+ public:
- ~Joint(void)
+
+ /** Possible geometry elements. These are assumed to be centered at origin (similar to ODE) */
+ struct Geometry
{
- if (after)
- delete after;
- }
+ Geometry(void)
+ {
+ type = UNKNOWN;
+ size[0] = size[1] = size[2] = 0.0;
+ }
+
+ enum
+ {
+ UNKNOWN, BOX, CYLINDER, SPHERE
+ } type;
+ double size[3];
+ };
- /* the links that this joint connects */
- Link *before;
- Link *after;
+ struct Joint;
+ struct Link;
- /* the range of indices in the parameter vector that
- needed to access information about the position of this
- joint */
- unsigned int usedParamStart;
- unsigned int usedParamEnd;
- bool active;
+ /** A joint from the robot. Contains the transform applied by the joint type */
+ struct Joint
+ {
+ Joint(void)
+ {
+ before = after = NULL;
+ usedParamStart = usedParamEnd = 0;
+ axis[0] = axis[1] = axis[2] = 0.0;
+ anchor[0] = anchor[1] = anchor[2] = 0.0;
+ limit[0] = limit[1] = 0.0;
+ type = UNKNOWN;
+ }
+
+ ~Joint(void)
+ {
+ if (after)
+ delete after;
+ }
+
+ /* the links that this joint connects */
+ Link *before;
+ Link *after;
+
+ /* the range of indices in the parameter vector that
+ needed to access information about the position of this
+ joint */
+ unsigned int usedParamStart;
+ unsigned int usedParamEnd;
+ bool active;
+
+ /* relevant joint information */
+ enum
+ {
+ UNKNOWN, FIXED, REVOLUTE, PRISMATIC, FLOATING
+ } type;
+ double axis[3];
+ double anchor[3];
+ double limit[2];
+
+ /* ----------------- Computed data -------------------*/
+
+ /* the local transform (computed by forward kinematics) */
+ libTF::Pose3D varTrans;
+ libTF::Pose3D globalTrans;
+
+ void computeTransform(const double *params);
+
+ };
- /* relevant joint information */
- enum
+ /** A link from the robot. Contains the constant transform applied to the link and its geometry */
+ struct Link
+ {
+ Link(void)
{
- UNKNOWN, FIXED, REVOLUTE, PRISMATIC, FLOATING
- } type;
- double axis[3];
- double anchor[3];
- double limit[2];
+ before = NULL;
+ geom = new Geometry();
+ }
+
+ ~Link(void)
+ {
+ if (geom)
+ delete geom;
+ for (unsigned int i = 0 ; i < after.size() ; ++i)
+ delete after[i];
+ }
+
+ /* joint that connects this link to the parent link */
+ Joint *before;
+
+ /* list of descending joints (each connects to a child link) */
+ std::vector<Joint*> after;
+
+ /* the constant transform applied to the link (local) */
+ libTF::Pose3D constTrans;
+
+ /* the constant transform applied to the collision geometry of the link (local) */
+ libTF::Pose3D constGeomTrans;
+
+ /* the geometry of the link */
+ Geometry *geom;
+
+ /* ----------------- Computed data -------------------*/
+
+ /* the global transform for this link (computed by forward kinematics) */
+ libTF::Pose3D globalTrans;
+
+ void computeTransform(const double *params);
+ };
- /* ----------------- Computed data -------------------*/
+ /** A robot structure */
+ struct Robot
+ {
+ Robot(void)
+ {
+ chain = NULL;
+ stateDimension = 0;
+ }
+
+ virtual ~Robot(void)
+ {
+ if (chain)
+ delete chain;
+ }
+
+ void computeTransforms(const double *params);
+
+ /** List of links in the robot */
+ std::vector<Link*> links;
+
+ /** List of leaf links (have no child links) */
+ std::vector<Link*> leafs;
+
+ /** The first joint in the robot -- the root */
+ Joint *chain;
+
+ /** Number of parameters needed to define the joints */
+ unsigned int stateDimension;
+
+ /** The bounding box for the set of parameters describing the
+ * joints. This array contains 2 * stateDimension elements:
+ * positions 2*i and 2*i+1 define the minimum and maximum
+ * values for the parameter. If both minimum and maximum are
+ * set to 0, the parameter is unbounded. */
+ std::vector<double> stateBounds;
+
+ /** Group of links corresponding to this robot (if any) */
+ std::string tag;
+
+ };
- /* the local transform (computed by forward kinematics) */
- libTF::Pose3D varTrans;
- libTF::Pose3D globalTrans;
-
- void computeTransform(const double *params);
-
- };
-
- /** A link from the robot. Contains the constant transform applied to the link and its geometry */
- struct Link
- {
- Link(void)
+ KinematicModel(void)
{
- before = NULL;
- geom = new Geometry();
+ m_verbose = false;
}
- ~Link(void)
+ virtual ~KinematicModel(void)
{
- if (geom)
- delete geom;
- for (unsigned int i = 0 ; i < after.size() ; ++i)
- delete after[i];
+ for (unsigned int i = 0 ; i < m_robots.size() ; ++i)
+ delete m_robots[i];
}
- /* joint that connects this link to the parent link */
- Joint *before;
+ virtual void build(URDF &model, const char *group = NULL);
- /* list of descending joints (each connects to a child link) */
- std::vector<Joint*> after;
+ unsigned int getRobotCount(void) const;
+ Robot* getRobot(unsigned int index) const;
- /* the constant transform applied to the link (local) */
- libTF::Pose3D constTrans;
-
- /* the constant transform applied to the collision geometry of the link (local) */
- libTF::Pose3D constGeomTrans;
-
- /* the geometry of the link */
- Geometry *geom;
+ protected:
- /* ----------------- Computed data -------------------*/
+ std::vector<Robot*> m_robots;
+ bool m_verbose;
- /* the global transform for this link (computed by forward kinematics) */
- libTF::Pose3D globalTrans;
-
- void computeTransform(const double *params);
- };
-
- /** A robot structure */
- struct Robot
- {
- Robot(void)
- {
- chain = NULL;
- stateDimension = 0;
- }
+ private:
- virtual ~Robot(void)
- {
- if (chain)
- delete chain;
- }
+ void buildChain(Robot *robot, Link *parent, Joint *joint, URDF::Link *urdfLink);
+ void buildChain(Robot *robot, Joint *parent, Link *link, URDF::Link *urdfLink);
- void computeTransforms(const double *params);
-
- /** List of links in the robot */
- std::vector<Link*> links;
-
- /** List of leaf links (have no child links) */
- std::vector<Link*> leafs;
-
- /** The first joint in the robot -- the root */
- Joint *chain;
-
- /** Number of parameters needed to define the joints */
- unsigned int stateDimension;
-
- /** The bounding box for the set of parameters describing the
- * joints. This array contains 2 * stateDimension elements:
- * positions 2*i and 2*i+1 define the minimum and maximum
- * values for the parameter. If both minimum and maximum are
- * set to 0, the parameter is unbounded. */
- std::vector<double> stateBounds;
-
- /** Group of links corresponding to this robot (if any) */
- std::string tag;
-
};
-
- KinematicModel(void)
- {
- m_verbose = false;
- }
-
- virtual ~KinematicModel(void)
- {
- for (unsigned int i = 0 ; i < m_robots.size() ; ++i)
- delete m_robots[i];
- }
-
- virtual void build(URDF &model, const char *group = NULL);
- unsigned int getRobotCount(void) const;
- Robot* getRobot(unsigned int index) const;
-
- protected:
-
- std::vector<Robot*> m_robots;
- bool m_verbose;
-
- private:
+}
- void buildChain(Robot *robot, Link *parent, Joint *joint, URDF::Link *urdfLink);
- void buildChain(Robot *robot, Joint *parent, Link *link, URDF::Link *urdfLink);
-
-};
-
#endif
Modified: pkg/trunk/util/robot_models/src/robot_models/kinematic.cpp
===================================================================
--- pkg/trunk/util/robot_models/src/robot_models/kinematic.cpp 2008-07-18 00:04:22 UTC (rev 1736)
+++ pkg/trunk/util/robot_models/src/robot_models/kinematic.cpp 2008-07-18 00:08:36 UTC (rev 1737)
@@ -35,13 +35,13 @@
#include <robot_models/kinematic.h>
#include <cstdio>
-void KinematicModel::Robot::computeTransforms(const double *params)
+void robot_models::KinematicModel::Robot::computeTransforms(const double *params)
{
chain->computeTransform(params);
}
// we can optimize things here... (when we use identity transforms, for example)
-void KinematicModel::Joint::computeTransform(const double *params)
+void robot_models::KinematicModel::Joint::computeTransform(const double *params)
{
switch (type)
{
@@ -73,7 +73,7 @@
after->computeTransform(params);
}
-void KinematicModel::Link::computeTransform(const double *params)
+void robot_models::KinematicModel::Link::computeTransform(const double *params)
{
globalTrans = before->globalTrans;
globalTrans.multiplyPose(constTrans);
@@ -82,7 +82,7 @@
globalTrans.multiplyPose(constGeomTrans);
}
-void KinematicModel::build(URDF &model, const char *group)
+void robot_models::KinematicModel::build(URDF &model, const char *group)
{
if (group)
{
@@ -110,17 +110,17 @@
}
}
-unsigned int KinematicModel::getRobotCount(void) const
+unsigned int robot_models::KinematicModel::getRobotCount(void) const
{
return m_robots.size();
}
-KinematicModel::Robot* KinematicModel::getRobot(unsigned int index) const
+robot_models::KinematicModel::Robot* robot_models::KinematicModel::getRobot(unsigned int index) const
{
return m_robots[index];
}
-void KinematicModel::buildChain(Robot *robot, Link *parent, Joint* joint, URDF::Link* urdfLink)
+void robot_models::KinematicModel::buildChain(Robot *robot, Link *parent, Joint* joint, URDF::Link* urdfLink)
{
joint->usedParamStart = robot->stateDimension;
joint->before = parent;
@@ -168,7 +168,7 @@
buildChain(robot, joint, joint->after, urdfLink);
}
-void KinematicModel::buildChain(Robot *robot, Joint *parent, Link* link, URDF::Link* urdfLink)
+void robot_models::KinematicModel::buildChain(Robot *robot, Joint *parent, Link* link, URDF::Link* urdfLink)
{
link->before = parent;
robot->links.push_back(link);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|