|
From: <is...@us...> - 2009-07-07 22:03:02
|
Revision: 18422
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18422&view=rev
Author: isucan
Date: 2009-07-07 22:02:57 +0000 (Tue, 07 Jul 2009)
Log Message:
-----------
update for ben
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-07 21:56:07 UTC (rev 18421)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-07 22:02:57 UTC (rev 18422)
@@ -51,8 +51,13 @@
CollisionModels(const std::string &description, double scale = 1.0, double padd = 0.0) : RobotModels(description), scale_(scale), padd_(padd)
{
- loadCollision();
+ loadCollision(collision_check_links_);
}
+
+ CollisionModels(const std::string &description, const std::vector<std::string> &links, double scale = 1.0, double padd = 0.0) : RobotModels(description), scale_(scale), padd_(padd)
+ {
+ loadCollision(links);
+ }
virtual ~CollisionModels(void)
{
@@ -63,7 +68,7 @@
{
RobotModels::reload();
ode_collision_model_.reset();
- loadCollision();
+ loadCollision(collision_check_links_);
}
/** \brief Return the instance of the constructed ODE collision model */
@@ -74,7 +79,7 @@
protected:
- void loadCollision(void);
+ void loadCollision(const std::vector<std::string> &links);
boost::shared_ptr<collision_space::EnvironmentModel> ode_collision_model_;
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-07 21:56:07 UTC (rev 18421)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-07 22:02:57 UTC (rev 18422)
@@ -36,13 +36,13 @@
#include "planning_environment/collision_models.h"
-void planning_environment::CollisionModels::loadCollision(void)
+void planning_environment::CollisionModels::loadCollision(const std::vector<std::string> &links)
{
if (loadedModels())
{
ode_collision_model_ = boost::shared_ptr<collision_space::EnvironmentModel>(new collision_space::EnvironmentModelODE());
ode_collision_model_->lock();
- ode_collision_model_->addRobotModel(kmodel_, collision_check_links_, scale_, padd_);
+ ode_collision_model_->addRobotModel(kmodel_, links, scale_, padd_);
// form all pairs of links that can collide and add them as self-collision groups
for (unsigned int i = 0 ; i < self_collision_check_groups_.size() ; ++i)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|