|
From: <is...@us...> - 2008-07-17 23:27:32
|
Revision: 1727
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1727&view=rev
Author: isucan
Date: 2008-07-17 23:27:36 +0000 (Thu, 17 Jul 2008)
Log Message:
-----------
remove dependecy on freesolid
Modified Paths:
--------------
pkg/trunk/util/megamaid/src/vacuum/vacuum.cpp
pkg/trunk/util/wg_collision_space/CMakeLists.txt
pkg/trunk/util/wg_collision_space/manifest.xml
Removed Paths:
-------------
pkg/trunk/3rdparty/freesolid/
pkg/trunk/util/wg_collision_space/include/collisionspace/environmentSOLID.h
pkg/trunk/util/wg_collision_space/src/collisionspace/environmentSOLID.cpp
Modified: pkg/trunk/util/megamaid/src/vacuum/vacuum.cpp
===================================================================
--- pkg/trunk/util/megamaid/src/vacuum/vacuum.cpp 2008-07-17 23:09:32 UTC (rev 1726)
+++ pkg/trunk/util/megamaid/src/vacuum/vacuum.cpp 2008-07-17 23:27:36 UTC (rev 1727)
@@ -64,6 +64,7 @@
map_name(vac_topics[i]),
start))
throw std::runtime_error("couldn't open log file\n");
+
subscribe(vac_topics[i], bags[i], &Vacuum::dummy_cb);
}
}
Modified: pkg/trunk/util/wg_collision_space/CMakeLists.txt
===================================================================
--- pkg/trunk/util/wg_collision_space/CMakeLists.txt 2008-07-17 23:09:32 UTC (rev 1726)
+++ pkg/trunk/util/wg_collision_space/CMakeLists.txt 2008-07-17 23:27:36 UTC (rev 1727)
@@ -1,7 +1,6 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
rospack(wg_collision_space)
-rospack_add_library(CollisionSpace src/collisionspace/environmentODE.cpp
- src/collisionspace/environmentSOLID.cpp)
+rospack_add_library(CollisionSpace src/collisionspace/environmentODE.cpp)
rospack_add_executable(test_kinematic_ode src/test/test_kinematic_ode.cpp)
target_link_libraries(test_kinematic_ode CollisionSpace)
Deleted: pkg/trunk/util/wg_collision_space/include/collisionspace/environmentSOLID.h
===================================================================
--- pkg/trunk/util/wg_collision_space/include/collisionspace/environmentSOLID.h 2008-07-17 23:09:32 UTC (rev 1726)
+++ pkg/trunk/util/wg_collision_space/include/collisionspace/environmentSOLID.h 2008-07-17 23:27:36 UTC (rev 1727)
@@ -1,154 +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.
-*********************************************************************/
-
-#ifndef KINEMATIC_ENVIRONMENT_MODEL_SOLID_
-#define KINEMATIC_ENVIRONMENT_MODEL_SOLID_
-
-#include <collisionspace/environment.h>
-#include <robotmodels/kinematic.h>
-#include <SOLID/solid.h>
-
-/** @htmlinclude ../../manifest.html
-
- A class describing an environment for a kinematic robot using SOLID */
-
-class EnvironmentModelSOLID : public EnvironmentModel
-{
- public:
-
- /* dummy object for SOLID object references */
- struct SOLIDObject
- {
- unsigned int id;
- };
-
- /* an object in the world */
- struct Object
- {
- Object(void)
- {
- obj = new SOLIDObject();
- shape = NULL;
- }
-
- ~Object(void)
- {
- if (obj && shape)
- {
- dtDeleteObject(obj);
- dtDeleteShape(shape);
- }
- if (obj)
- delete obj;
- }
-
- SOLIDObject *obj;
- DtShapeRef shape;
- };
-
- class KinematicModelSOLID : public KinematicModel
- {
- public:
-
- KinematicModelSOLID(void) : KinematicModel()
- {
- }
-
- virtual ~KinematicModelSOLID(void)
- {
- for (unsigned int i = 0 ; i < m_kshapes.size() ; ++i)
- delete m_kshapes[i];
- }
-
- virtual void build(URDF &model, const char *group = NULL);
-
- unsigned int getObjectCount(void) const;
- Object* getObject(unsigned int index) const;
-
- void updateCollisionPositions(void);
-
- protected:
-
- struct kShape
- {
- kShape(void)
- {
- obj = new Object();
- link = NULL;
- }
-
- ~kShape(void)
- {
- if (obj)
- delete obj;
- }
-
- Object *obj;
- Link *link;
- };
-
- std::vector<kShape*> m_kshapes;
-
- void buildSOLIDShapes(Robot *robot);
- DtShapeRef buildSOLIDShape(Geometry *geom);
-
- };
-
-
- EnvironmentModelSOLID(void) : EnvironmentModel()
- {
- model = dynamic_cast<KinematicModel*>(&m_modelSOLID);
- }
-
- ~EnvironmentModelSOLID(void)
- {
- for (unsigned int i = 0 ; i < m_obstacles.size() ; ++i)
- delete m_obstacles[i];
- }
-
- /** Check if the model is in collision */
- virtual bool isCollision(void);
-
- /** Add a point cloud to the collision space */
- virtual void addPointCloud(unsigned int n, const double *points, double radius = 0.01);
-
- protected:
-
- KinematicModelSOLID m_modelSOLID;
- std::vector<Object*> m_obstacles;
-
-
-};
-
-#endif
Modified: pkg/trunk/util/wg_collision_space/manifest.xml
===================================================================
--- pkg/trunk/util/wg_collision_space/manifest.xml 2008-07-17 23:09:32 UTC (rev 1726)
+++ pkg/trunk/util/wg_collision_space/manifest.xml 2008-07-17 23:27:36 UTC (rev 1727)
@@ -7,7 +7,6 @@
<license>BSD</license>
<depend package="wg_robot_models"/>
- <depend package="freesolid"/>
<depend package="opende"/>
<depend package="drawstuff"/>
Deleted: pkg/trunk/util/wg_collision_space/src/collisionspace/environmentSOLID.cpp
===================================================================
--- pkg/trunk/util/wg_collision_space/src/collisionspace/environmentSOLID.cpp 2008-07-17 23:09:32 UTC (rev 1726)
+++ pkg/trunk/util/wg_collision_space/src/collisionspace/environmentSOLID.cpp 2008-07-17 23:27:36 UTC (rev 1727)
@@ -1,154 +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 <collisionspace/environmentSOLID.h>
-
-bool EnvironmentModelSOLID::isCollision(void)
-{
- return dtTest();
-}
-
-void EnvironmentModelSOLID::addPointCloud(unsigned int n, const double *points, double radius)
-{
- Object *obj = new Object();
- obj->shape = dtNewComplexShape();
-
- for (unsigned int i = 0 ; i < n ; ++i)
- {
- unsigned int i3 = i * 3;
- double x = points[i3 ];
- double y = points[i3 + 1];
- double z = points[i3 + 2];
-
- dtBegin(DT_SIMPLEX);
- dtVertex(x, y, z + radius);
- dtVertex(x - radius, y - radius, z - radius);
- dtVertex(x + radius, y - radius, z - radius);
- dtEnd();
-
- dtBegin(DT_SIMPLEX);
- dtVertex(x - radius, y - radius, z - radius);
- dtVertex(x + radius, y - radius, z - radius);
- dtVertex(x + radius, y + radius, z - radius);
- dtEnd();
-
- dtBegin(DT_SIMPLEX);
- dtVertex(x, y, z + radius);
- dtVertex(x + radius, y - radius, z - radius);
- dtVertex(x + radius, y + radius, z - radius);
- dtEnd();
-
- dtBegin(DT_SIMPLEX);
- dtVertex(x, y, z + radius);
- dtVertex(x + radius, y - radius, z - radius);
- dtVertex(x - radius, y - radius, z - radius);
- dtEnd();
- }
-
- dtEndComplexShape();
- dtCreateObject(obj->obj, obj->shape);
-}
-
-void EnvironmentModelSOLID::KinematicModelSOLID::build(URDF &model, const char *group)
-{
- KinematicModel::build(model, group);
- for (unsigned int i = 0 ; i < m_robots.size() ; ++i)
- buildSOLIDShapes(m_robots[i]);
- dtDisableCaching();
-}
-
-void EnvironmentModelSOLID::KinematicModelSOLID::buildSOLIDShapes(Robot *robot)
-{
- for (unsigned int i = 0 ; i < robot->links.size() ; ++i)
- {
- kShape *ks = new kShape();
- ks->link = robot->links[i];
- ks->obj->shape = buildSOLIDShape(robot->links[i]->geom);
- if (!ks->obj->shape)
- {
- delete ks;
- continue;
- }
-
- dtCreateObject(ks->obj->obj, ks->obj->shape);
- m_kshapes.push_back(ks);
- }
-}
-
-DtShapeRef EnvironmentModelSOLID::KinematicModelSOLID::buildSOLIDShape(Geometry *geom)
-{
- DtShapeRef g = NULL;
-
- switch (geom->type)
- {
- case Geometry::SPHERE:
- g = dtSphere(geom->size[0]);
- break;
- case Geometry::BOX:
- g = dtBox(geom->size[0], geom->size[1], geom->size[2]);
- break;
- case Geometry::CYLINDER:
- g = dtCylinder(geom->size[0], geom->size[1]);
- break;
- default:
- break;
- }
-
- return g;
-}
-
-void EnvironmentModelSOLID::KinematicModelSOLID::updateCollisionPositions(void)
-{
- for (unsigned int i = 0 ; i < m_kshapes.size() ; ++i)
- {
- dtSelectObject(m_kshapes[i]->obj->obj);
- libTF::Pose3D::Position pos;
- m_kshapes[i]->link->globalTrans.getPosition(pos);
- libTF::Pose3D::Quaternion quat;
- m_kshapes[i]->link->globalTrans.getQuaternion(quat);
- dtLoadIdentity();
- dtTranslate(pos.x, pos.y, pos.z);
- dtRotate(quat.x, quat.y, quat.z, quat.w);
- }
-}
-
-unsigned int EnvironmentModelSOLID::KinematicModelSOLID::getObjectCount(void) const
-{
- return m_kshapes.size();
-}
-
-EnvironmentModelSOLID::Object* EnvironmentModelSOLID::KinematicModelSOLID::getObject(unsigned int index) const
-{
- return m_kshapes[index]->obj;
-}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|