|
From: <is...@us...> - 2008-07-25 21:11:40
|
Revision: 2141
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2141&view=rev
Author: isucan
Date: 2008-07-25 21:11:48 +0000 (Fri, 25 Jul 2008)
Log Message:
-----------
separated display utility as well
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/util/test_collision_space/manifest.xml
pkg/trunk/util/test_collision_space/src/test_kinematic_ode.cpp
Added Paths:
-----------
pkg/trunk/util/display_ode_spaces/
pkg/trunk/util/display_ode_spaces/CMakeLists.txt
pkg/trunk/util/display_ode_spaces/Makefile
pkg/trunk/util/display_ode_spaces/include/
pkg/trunk/util/display_ode_spaces/include/display_ode/
pkg/trunk/util/display_ode_spaces/include/display_ode/displayODE.h
pkg/trunk/util/display_ode_spaces/manifest.xml
pkg/trunk/util/display_ode_spaces/src/
pkg/trunk/util/display_ode_spaces/src/displayODE.cpp
Removed Paths:
-------------
pkg/trunk/util/test_collision_space/src/displayODE.h
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-25 20:56:01 UTC (rev 2140)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-25 21:11:48 UTC (rev 2141)
@@ -104,7 +104,8 @@
subscribe("world_3d_map", m_cloud, &KinematicPlanning::pointCloudCallback);
m_collisionSpace = new collision_space::EnvironmentModelODE();
-
+ m_collisionSpace->setSelfCollision(false); // for now, disable self collision (incorrect model)
+
m_collisionSpace->lock();
loadRobotDescriptions();
m_collisionSpace->unlock();
Modified: pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp 2008-07-25 20:56:01 UTC (rev 2140)
+++ pkg/trunk/util/collision_space/src/collision_space/environmentODE.cpp 2008-07-25 21:11:48 UTC (rev 2141)
@@ -178,7 +178,6 @@
return m_kgeoms[model_id].s;
}
-
struct CollisionData
{
bool collides;
Added: pkg/trunk/util/display_ode_spaces/CMakeLists.txt
===================================================================
--- pkg/trunk/util/display_ode_spaces/CMakeLists.txt (rev 0)
+++ pkg/trunk/util/display_ode_spaces/CMakeLists.txt 2008-07-25 21:11:48 UTC (rev 2141)
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(display_ode_spaces)
+
+rospack_add_library(display_ODE_space src/displayODE.cpp)
Added: pkg/trunk/util/display_ode_spaces/Makefile
===================================================================
--- pkg/trunk/util/display_ode_spaces/Makefile (rev 0)
+++ pkg/trunk/util/display_ode_spaces/Makefile 2008-07-25 21:11:48 UTC (rev 2141)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Copied: pkg/trunk/util/display_ode_spaces/include/display_ode/displayODE.h (from rev 2137, pkg/trunk/util/test_collision_space/src/displayODE.h)
===================================================================
--- pkg/trunk/util/display_ode_spaces/include/display_ode/displayODE.h (rev 0)
+++ pkg/trunk/util/display_ode_spaces/include/display_ode/displayODE.h 2008-07-25 21:11:48 UTC (rev 2141)
@@ -0,0 +1,123 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include <ode/ode.h>
+#include <drawstuff/drawstuff.h>
+#include <vector>
+
+#ifdef dDOUBLE
+#define dsDrawBox dsDrawBoxD
+#define dsDrawSphere dsDrawSphereD
+#define dsDrawTriangle dsDrawTriangleD
+#define dsDrawCylinder dsDrawCylinderD
+#define dsDrawCapsule dsDrawCapsuleD
+#define dsDrawLine dsDrawLineD
+#define dsDrawConvex dsDrawConvexD
+#endif
+
+namespace display_ode
+{
+
+ class DisplayODESpaces
+ {
+ public:
+
+ void drawSphere(dGeomID geom)
+ {
+ dReal radius = dGeomSphereGetRadius(geom);
+ dsDrawSphere(dGeomGetPosition(geom), dGeomGetRotation(geom), radius);
+ }
+
+ void drawBox(dGeomID geom)
+ {
+ dVector3 sides;
+ dGeomBoxGetLengths(geom, sides);
+ dsDrawBox(dGeomGetPosition(geom), dGeomGetRotation(geom), sides);
+ }
+
+ void drawCylinder(dGeomID geom)
+ {
+ dReal radius, length;
+ dGeomCylinderGetParams(geom, &radius, &length);
+ dsDrawCylinder(dGeomGetPosition(geom), dGeomGetRotation(geom), length, radius);
+ }
+
+ void displaySpace(dSpaceID space)
+ {
+ int ngeoms = dSpaceGetNumGeoms(space);
+ for (int i = 0 ; i < ngeoms ; ++i)
+ {
+ dGeomID geom = dSpaceGetGeom(space, i);
+ int cls = dGeomGetClass(geom);
+ switch (cls)
+ {
+ case dSphereClass:
+ drawSphere(geom);
+ break;
+ case dBoxClass:
+ drawBox(geom);
+ break;
+ case dCylinderClass:
+ drawCylinder(geom);
+ break;
+ default:
+ printf("Geometry class %d not yet implemented\n", cls);
+ break;
+ }
+ }
+ }
+
+ void displaySpaces(void)
+ {
+ for (unsigned int i = 0 ; i < m_spaces.size() ; ++i)
+ displaySpace(m_spaces[i]);
+ }
+
+ void addSpace(dSpaceID space)
+ {
+ m_spaces.push_back(space);
+ }
+
+ void clear(void)
+ {
+ m_spaces.clear();
+ }
+
+ protected:
+
+ std::vector<dSpaceID> m_spaces;
+
+ };
+
+}
Added: pkg/trunk/util/display_ode_spaces/manifest.xml
===================================================================
--- pkg/trunk/util/display_ode_spaces/manifest.xml (rev 0)
+++ pkg/trunk/util/display_ode_spaces/manifest.xml 2008-07-25 21:11:48 UTC (rev 2141)
@@ -0,0 +1,15 @@
+<package>
+ <description brief="Simple library for displaying ODE spaces">
+ Given a set of ODE spaces, display them using the drawstuff library
+ </description>
+
+ <author>Ioan Sucan/is...@wi...</author>
+ <license>BSD</license>
+
+ <depend package="drawstuff"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -ldisplay_ODE_space"/>
+ </export>
+
+</package>
Added: pkg/trunk/util/display_ode_spaces/src/displayODE.cpp
===================================================================
--- pkg/trunk/util/display_ode_spaces/src/displayODE.cpp (rev 0)
+++ pkg/trunk/util/display_ode_spaces/src/displayODE.cpp 2008-07-25 21:11:48 UTC (rev 2141)
@@ -0,0 +1,35 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include <display_ode/displayODE.h>
Modified: pkg/trunk/util/test_collision_space/manifest.xml
===================================================================
--- pkg/trunk/util/test_collision_space/manifest.xml 2008-07-25 20:56:01 UTC (rev 2140)
+++ pkg/trunk/util/test_collision_space/manifest.xml 2008-07-25 21:11:48 UTC (rev 2141)
@@ -7,6 +7,6 @@
<license>BSD</license>
<depend package="collision_space"/>
- <depend package="drawstuff"/>
+ <depend package="display_ode_spaces"/>
</package>
Deleted: pkg/trunk/util/test_collision_space/src/displayODE.h
===================================================================
--- pkg/trunk/util/test_collision_space/src/displayODE.h 2008-07-25 20:56:01 UTC (rev 2140)
+++ pkg/trunk/util/test_collision_space/src/displayODE.h 2008-07-25 21:11:48 UTC (rev 2141)
@@ -1,119 +0,0 @@
-/*********************************************************************
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2008, Willow Garage, Inc.
-* All rights reserved.
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-*
-* * Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* * Redistributions in binary form must reproduce the above
-* copyright notice, this list of conditions and the following
-* disclaimer in the documentation and/or other materials provided
-* with the distribution.
-* * Neither the name of the Willow Garage nor the names of its
-* contributors may be used to endorse or promote products derived
-* from this software without specific prior written permission.
-*
-* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-* POSSIBILITY OF SUCH DAMAGE.
-*********************************************************************/
-
-#include <ode/ode.h>
-#include <drawstuff/drawstuff.h>
-#include <vector>
-
-#ifdef dDOUBLE
-#define dsDrawBox dsDrawBoxD
-#define dsDrawSphere dsDrawSphereD
-#define dsDrawTriangle dsDrawTriangleD
-#define dsDrawCylinder dsDrawCylinderD
-#define dsDrawCapsule dsDrawCapsuleD
-#define dsDrawLine dsDrawLineD
-#define dsDrawConvex dsDrawConvexD
-#endif
-
-class DisplayODESpaces
-{
- public:
-
- void drawSphere(dGeomID geom)
- {
- dReal radius = dGeomSphereGetRadius(geom);
- dsDrawSphere(dGeomGetPosition(geom), dGeomGetRotation(geom), radius);
- }
-
- void drawBox(dGeomID geom)
- {
- dVector3 sides;
- dGeomBoxGetLengths(geom, sides);
- dsDrawBox(dGeomGetPosition(geom), dGeomGetRotation(geom), sides);
- }
-
- void drawCylinder(dGeomID geom)
- {
- dReal radius, length;
- dGeomCylinderGetParams(geom, &radius, &length);
- dsDrawCylinder(dGeomGetPosition(geom), dGeomGetRotation(geom), length, radius);
- }
-
- void displaySpace(dSpaceID space)
- {
- int ngeoms = dSpaceGetNumGeoms(space);
- for (int i = 0 ; i < ngeoms ; ++i)
- {
- dGeomID geom = dSpaceGetGeom(space, i);
- int cls = dGeomGetClass(geom);
- switch (cls)
- {
- case dSphereClass:
- drawSphere(geom);
- break;
- case dBoxClass:
- drawBox(geom);
- break;
- case dCylinderClass:
- drawCylinder(geom);
- break;
- default:
- printf("Geometry class %d not yet implemented\n", cls);
- break;
- }
- }
- }
-
- void displaySpaces(void)
- {
- for (unsigned int i = 0 ; i < m_spaces.size() ; ++i)
- displaySpace(m_spaces[i]);
- }
-
- void addSpace(dSpaceID space)
- {
- m_spaces.push_back(space);
- }
-
- void clear(void)
- {
- m_spaces.clear();
- }
-
- protected:
-
- std::vector<dSpaceID> m_spaces;
-
-};
-
Modified: pkg/trunk/util/test_collision_space/src/test_kinematic_ode.cpp
===================================================================
--- pkg/trunk/util/test_collision_space/src/test_kinematic_ode.cpp 2008-07-25 20:56:01 UTC (rev 2140)
+++ pkg/trunk/util/test_collision_space/src/test_kinematic_ode.cpp 2008-07-25 21:11:48 UTC (rev 2141)
@@ -33,8 +33,9 @@
*********************************************************************/
#include <collision_space/environmentODE.h>
-#include "displayODE.h"
+#include <display_ode/displayODE.h>
using namespace collision_space;
+using namespace display_ode;
static DisplayODESpaces spaces;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|