|
From: <is...@us...> - 2009-02-20 23:30:39
|
Revision: 11483
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=11483&view=rev
Author: isucan
Date: 2009-02-20 23:30:35 +0000 (Fri, 20 Feb 2009)
Log Message:
-----------
enabling compiler optimization
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPProjectionEvaluators.h
pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPStateValidator.h
pkg/trunk/motion_planning/kinematic_planning/manifest.xml
pkg/trunk/motion_planning/ompl/CMakeLists.txt
pkg/trunk/world_models/robot_models/collision_space/CMakeLists.txt
pkg/trunk/world_models/robot_models/planning_models/CMakeLists.txt
Modified: pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-02-20 23:30:35 UTC (rev 11483)
@@ -104,7 +104,7 @@
double evaluateGoalAux(ompl::SpaceInformationKinematic::StateKinematic_t state, std::vector<bool> *decision) const
{
- m_model->lock.lock();
+ m_model->kmodel->lock();
update(state);
if (decision)
@@ -118,7 +118,7 @@
(*decision)[i] = m_pce[i]->decide(dPos, dAng);
distance += dPos + m_pce[i]->getConstraintMessage().orientation_importance * dAng;
}
- m_model->lock.unlock();
+ m_model->kmodel->unlock();
return distance;
}
Modified: pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPProjectionEvaluators.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPProjectionEvaluators.h 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPProjectionEvaluators.h 2009-02-20 23:30:35 UTC (rev 11483)
@@ -64,13 +64,13 @@
virtual void operator()(const ompl::SpaceInformation::State *state, double *projection) const
{
const ompl::SpaceInformationKinematic::StateKinematic *kstate = static_cast<const ompl::SpaceInformationKinematic::StateKinematic*>(state);
- m_model->lock.lock();
+ m_model->kmodel->lock();
m_model->kmodel->computeTransformsGroup(kstate->values, m_model->groupID);
const btVector3 &origin = m_link->globalTrans.getOrigin();
projection[0] = origin.x();
projection[1] = origin.y();
projection[2] = origin.z();
- m_model->lock.unlock();
+ m_model->kmodel->unlock();
}
protected:
Modified: pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPStateValidator.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPStateValidator.h 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPStateValidator.h 2009-02-20 23:30:35 UTC (rev 11483)
@@ -56,7 +56,7 @@
virtual bool operator()(const ompl::SpaceInformation::State_t state) const
{
- m_model->lock.lock();
+ m_model->kmodel->lock();
m_model->kmodel->computeTransformsGroup(static_cast<const ompl::SpaceInformationKinematic::StateKinematic_t>(state)->values, m_model->groupID);
m_model->collisionSpace->updateRobotModel(m_model->collisionSpaceID);
@@ -64,7 +64,7 @@
if (valid)
valid = m_kce.decide();
- m_model->lock.unlock();
+ m_model->kmodel->unlock();
return valid;
}
Modified: pkg/trunk/motion_planning/kinematic_planning/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/manifest.xml 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/motion_planning/kinematic_planning/manifest.xml 2009-02-20 23:30:35 UTC (rev 11483)
@@ -20,7 +20,7 @@
<depend package="ompl" />
<export>
- <cpp cflags="-I${prefix}/include `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lkinematic_planning_helpers"/>
+ <cpp cflags="-I${prefix}/include `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lkinematic_planning_helpers `rosboost-cfg --lflags thread`"/>
</export>
</package>
Modified: pkg/trunk/motion_planning/ompl/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/ompl/CMakeLists.txt 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/motion_planning/ompl/CMakeLists.txt 2009-02-20 23:30:35 UTC (rev 11483)
@@ -3,7 +3,7 @@
rospack(ompl)
rospack_add_boost_directories()
include_directories(${PROJECT_SOURCE_DIR}/code)
-#set(CMAKE_BUILD_TYPE Release)
+set(CMAKE_BUILD_TYPE Release)
rospack_add_library(ompl code/ompl/base/util/src/time.cpp
code/ompl/base/util/src/output.cpp
code/ompl/base/util/src/random_utils.cpp
Modified: pkg/trunk/world_models/robot_models/collision_space/CMakeLists.txt
===================================================================
--- pkg/trunk/world_models/robot_models/collision_space/CMakeLists.txt 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/world_models/robot_models/collision_space/CMakeLists.txt 2009-02-20 23:30:35 UTC (rev 11483)
@@ -4,8 +4,9 @@
rospack_add_boost_directories()
+set(CMAKE_BUILD_TYPE Release)
+
rospack_add_library(collision_space src/collision_space/environment.cpp
-# src/collision_space/environmentOctree.cpp
src/collision_space/environmentODE.cpp)
rospack_link_boost(collision_space thread)
Modified: pkg/trunk/world_models/robot_models/planning_models/CMakeLists.txt
===================================================================
--- pkg/trunk/world_models/robot_models/planning_models/CMakeLists.txt 2009-02-20 23:15:33 UTC (rev 11482)
+++ pkg/trunk/world_models/robot_models/planning_models/CMakeLists.txt 2009-02-20 23:30:35 UTC (rev 11483)
@@ -2,6 +2,9 @@
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
rospack(planning_models)
rospack_add_boost_directories()
+
+set(CMAKE_BUILD_TYPE Release)
+
rospack_add_library(planning_models src/kinematic.cpp)
# Unit tests
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|