|
From: <is...@us...> - 2008-09-05 17:19:35
|
Revision: 3982
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3982&view=rev
Author: isucan
Date: 2008-09-05 17:19:44 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
more docs on collision spaces, renamed a function
Modified Paths:
--------------
pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_
@@ -45,7 +45,13 @@
/** @htmlinclude ../../manifest.html
- A class describing an environment for a kinematic robot */
+ A class describing an environment for a kinematic robot. This is
+ the base (abstract) definition. Different implementations are
+ possible. The class is aware of a certain set of fixed
+ (addStatic*) obstacles that never change, a set of obstacles that
+ can change (removed by clearObstacles()) and a set of kinematic
+ robots. The class provides functionality for checking whether a
+ given robot is in collision. */
namespace collision_space
{
@@ -75,7 +81,7 @@
virtual void addPointCloud(unsigned int n, const double* points, double radius = 0.01) = 0;
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d) = 0;
+ virtual void addStaticPlane(double a, double b, double c, double d) = 0;
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
@@ -84,7 +84,7 @@
virtual void addPointCloud(unsigned int n, const double *points, double radius = 0.01);
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d);
+ virtual void addStaticPlane(double a, double b, double c, double d);
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan, Matei Ciocarlie */
+/** \author Ioan Sucan, Matei Ciocarlie */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
@@ -76,7 +76,7 @@
virtual void addPointCloud(unsigned int n, const double *points, double radius = 0.01);
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d);
+ virtual void addStaticPlane(double a, double b, double c, double d);
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_UTIL_
#define COLLISION_SPACE_UTIL_
@@ -40,6 +40,14 @@
#include <libTF/Pose3D.h>
#include <cmath>
+/**
+ This set of classes allows quickly detecting whether a given point
+ is inside an object or not. Only basic (simple) types of objects
+ are supported: spheres, cylinders, boxes. This capability is useful
+ when removing points from inside the robot (when the robot sees its
+ arms, for example).
+*/
+
namespace collision_space
{
@@ -78,7 +86,7 @@
bool containsPoint(double x, double y, double z) const
{
- libTF::Position pt(x, y, z);
+ libTF::Position pt(x, y, z);
return containsPoint(pt);
}
@@ -129,8 +137,8 @@
}
libTF::Position m_center;
- double m_radius;
- double m_radius2;
+ double m_radius;
+ double m_radius2;
};
@@ -178,6 +186,8 @@
m_pose.getPosition(m_center);
+ // this can probably be optimized by simply taking
+ // the columns of the transform matrix
m_normalH.x = m_normalH.y = 0.0; m_normalH.z = 1.0;
m_pose.applyToVector(m_normalH);
@@ -193,10 +203,10 @@
libTF::Vector m_normalB1;
libTF::Vector m_normalB2;
- double m_length;
- double m_length2;
- double m_radius;
- double m_radius2;
+ double m_length;
+ double m_length2;
+ double m_radius;
+ double m_radius2;
};
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include <collision_space/environment.h>
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include <collision_space/environmentODE.h>
#include <algorithm>
@@ -391,7 +391,7 @@
m_collide2.setup();
}
-void collision_space::EnvironmentModelODE::addPlane(double a, double b, double c, double d)
+void collision_space::EnvironmentModelODE::addStaticPlane(double a, double b, double c, double d)
{
dGeomID g = dCreatePlane(m_spaceBasicGeoms, a, b, c, d);
m_basicGeoms.push_back(g);
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan, Matei Ciocarlie */
+/** \author Ioan Sucan, Matei Ciocarlie */
#include <collision_space/environmentOctree.h>
@@ -148,7 +148,7 @@
return &m_octree;
}
-void collision_space::EnvironmentModelOctree::addPlane(double a, double b, double c, double d)
+void collision_space::EnvironmentModelOctree::addStaticPlane(double a, double b, double c, double d)
{
fprintf(stderr, "Octree collision checking does not support planes\n");
}
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
@@ -94,7 +94,7 @@
else
m_collisionSpace = new collision_space::EnvironmentModelODE();
m_collisionSpace->setSelfCollision(true);
- m_collisionSpace->addPlane(0.0, 0.0, 1.0, -0.01);
+ m_collisionSpace->addStaticPlane(0.0, 0.0, 1.0, -0.01);
m_sphereSize = 0.03;
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|