|
From: <is...@us...> - 2009-06-21 23:28:45
|
Revision: 17434
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17434&view=rev
Author: isucan
Date: 2009-06-21 23:28:43 +0000 (Sun, 21 Jun 2009)
Log Message:
-----------
enabled automatic planner selection
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/move_arm.cpp
pkg/trunk/motion_planning/ompl_planning/CMakeLists.txt
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPPlannerSetup.h
pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPRequestHandler.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPPlannerSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp
pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml
Added Paths:
-----------
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPLBKPIECESetup.h
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp
Modified: pkg/trunk/highlevel/move_arm/src/move_arm.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -63,7 +63,7 @@
{
node_handle_.param<std::string>("~arm", arm_, std::string());
node_handle_.param<bool>("~perform_ik", perform_ik_, true);
-
+
// monitor robot
collisionModels_ = new planning_environment::CollisionModels("robot_description");
planningMonitor_ = new planning_environment::PlanningMonitor(collisionModels_);
@@ -112,7 +112,6 @@
req.params.model_id = arm_; // the model to plan for (should be defined in planning.yaml)
- req.params.planner_id = "KPIECE"; // this is optional; the planning node should be able to pick a planner
req.params.distance_metric = "L2Square"; // the metric to be used in the robot's state space
// this volume is only needed if planar or floating joints move in the space
Modified: pkg/trunk/motion_planning/ompl_planning/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/CMakeLists.txt 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/CMakeLists.txt 2009-06-21 23:28:43 UTC (rev 17434)
@@ -13,6 +13,7 @@
src/helpers/ompl_planner/RKPRRTSetup.cpp
src/helpers/ompl_planner/RKPIKKPIECESetup.cpp
src/helpers/ompl_planner/RKPKPIECESetup.cpp
+ src/helpers/ompl_planner/RKPLBKPIECESetup.cpp
src/helpers/ompl_planner/RKPSBLSetup.cpp
src/helpers/ompl_extensions/RKPGoalDefinitions.cpp
src/helpers/ompl_extensions/RKPSpaceInformation.cpp
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h 2009-06-21 23:28:43 UTC (rev 17434)
@@ -45,6 +45,7 @@
#include "kinematic_planning/ompl_planner/RKPESTSetup.h"
#include "kinematic_planning/ompl_planner/RKPIKSBLSetup.h"
#include "kinematic_planning/ompl_planner/RKPKPIECESetup.h"
+#include "kinematic_planning/ompl_planner/RKPLBKPIECESetup.h"
#include "kinematic_planning/ompl_planner/RKPIKKPIECESetup.h"
#include <boost/shared_ptr.hpp>
@@ -81,6 +82,7 @@
void addSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
void addIKSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
void addKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void addLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
void addIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
};
Added: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPLBKPIECESetup.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPLBKPIECESetup.h (rev 0)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPLBKPIECESetup.h 2009-06-21 23:28:43 UTC (rev 17434)
@@ -0,0 +1,58 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+/** \author Ioan Sucan */
+
+#ifndef KINEMATIC_PLANNING_OMPL_PLANNER_RKP_LBKPIECE_SETUP_
+#define KINEMATIC_PLANNING_OMPL_PLANNER_RKP_LBKPIECE_SETUP_
+
+#include "kinematic_planning/ompl_planner/RKPPlannerSetup.h"
+#include <ompl/extension/samplingbased/kinematic/extension/kpiece/LBKPIECE1.h>
+
+namespace kinematic_planning
+{
+
+ class RKPLBKPIECESetup : public RKPPlannerSetup
+ {
+ public:
+
+ RKPLBKPIECESetup(RKPModelBase *m);
+ virtual ~RKPLBKPIECESetup(void);
+ virtual bool setup(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ };
+
+} // kinematic_planning
+
+#endif
+
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPPlannerSetup.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPPlannerSetup.h 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_planner/RKPPlannerSetup.h 2009-06-21 23:28:43 UTC (rev 17434)
@@ -77,13 +77,14 @@
RKPModelBase *model;
- std::string name;
- ompl::sb::Planner *mp;
- ompl::sb::GAIK *gaik;
- ompl::sb::SpaceInformationKinematic *si;
- ompl::base::StateValidityChecker *svc;
- std::map<std::string, ompl::base::StateDistanceEvaluator*> sde;
- ompl::sb::PathSmootherKinematic *smoother;
+ std::string name; // name of planner
+ ompl::sb::Planner *mp; // pointer to OMPL instance of planner
+ int priority; // priority of this planner when automatically selecting planners
+ ompl::sb::GAIK *gaik; // tool for performing general IK
+ ompl::sb::SpaceInformationKinematic *si; // space information for the planner
+ ompl::base::StateValidityChecker *svc; // the state validation routine
+ std::map<std::string, ompl::base::StateDistanceEvaluator*> sde; // list of available distance evaluators
+ ompl::sb::PathSmootherKinematic *smoother; // pointer to an OMPL path smoother
};
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -58,13 +58,16 @@
if (type == "KPIECE")
addKPIECE(cfgs[i]);
else
- if (type == "IKSBL")
- addIKSBL(cfgs[i]);
+ if (type == "LBKPIECE")
+ addLBKPIECE(cfgs[i]);
else
- if (type == "IKKPIECE")
- addIKKPIECE(cfgs[i]);
+ if (type == "IKSBL")
+ addIKSBL(cfgs[i]);
else
- ROS_WARN("Unknown planner type: %s", type.c_str());
+ if (type == "IKKPIECE")
+ addIKKPIECE(cfgs[i]);
+ else
+ ROS_WARN("Unknown planner type: %s", type.c_str());
}
}
@@ -122,7 +125,16 @@
delete kpiece;
}
+void kinematic_planning::RKPModel::addLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+{
+ RKPPlannerSetup *kpiece = new RKPLBKPIECESetup(dynamic_cast<RKPModelBase*>(this));
+ if (kpiece->setup(options))
+ planners[kpiece->name] = kpiece;
+ else
+ delete kpiece;
+}
+
void kinematic_planning::RKPModel::addIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *kpiece = new RKPIKKPIECESetup(dynamic_cast<RKPModelBase*>(this));
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPRequestHandler.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPRequestHandler.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPRequestHandler.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -54,11 +54,17 @@
/* if the user did not specify a planner, use the first available one */
if (req.params.planner_id.empty())
- {
- if (!m->planners.empty())
- req.params.planner_id = m->planners.begin()->first;
- }
-
+ for (std::map<std::string, RKPPlannerSetup*>::const_iterator it = m->planners.begin() ; it != m->planners.end() ; ++it)
+ if ((req.goal_constraints.pose_constraint.empty() && (it->second->mp->getType() & ompl::sb::PLAN_TO_GOAL_STATE) != 0) ||
+ (!req.goal_constraints.pose_constraint.empty() && (it->second->mp->getType() & ompl::sb::PLAN_TO_GOAL_REGION) != 0))
+ {
+ if (req.params.planner_id.empty())
+ req.params.planner_id = it->first;
+ else
+ if (m->planners[req.params.planner_id]->priority < it->second->priority)
+ req.params.planner_id = it->first;
+ }
+
/* check if desired planner exists */
std::map<std::string, RKPPlannerSetup*>::iterator plannerIt = m->planners.find(req.params.planner_id);
if (plannerIt == m->planners.end())
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -40,6 +40,7 @@
kinematic_planning::RKPESTSetup::RKPESTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
name = "EST";
+ priority = 1;
}
kinematic_planning::RKPESTSetup::~RKPESTSetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -38,7 +38,8 @@
kinematic_planning::RKPIKKPIECESetup::RKPIKKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "IKKPIECE";
+ name = "IKKPIECE";
+ priority = 5;
}
kinematic_planning::RKPIKKPIECESetup::~RKPIKKPIECESetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -38,7 +38,8 @@
kinematic_planning::RKPIKSBLSetup::RKPIKSBLSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "IKSBL";
+ name = "IKSBL";
+ priority = 4;
}
kinematic_planning::RKPIKSBLSetup::~RKPIKSBLSetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -39,6 +39,7 @@
kinematic_planning::RKPKPIECESetup::RKPKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
name = "KPIECE";
+ priority = 3;
}
kinematic_planning::RKPKPIECESetup::~RKPKPIECESetup(void)
Added: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp (rev 0)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -0,0 +1,80 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+/** \author Ioan Sucan */
+
+#include "kinematic_planning/ompl_planner/RKPLBKPIECESetup.h"
+
+kinematic_planning::RKPLBKPIECESetup::RKPLBKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
+{
+ name = "LBKPIECE";
+ priority = 11;
+}
+
+kinematic_planning::RKPLBKPIECESetup::~RKPLBKPIECESetup(void)
+{
+ if (dynamic_cast<ompl::sb::LBKPIECE1*>(mp))
+ {
+ ompl::base::ProjectionEvaluator *pe = dynamic_cast<ompl::sb::LBKPIECE1*>(mp)->getProjectionEvaluator();
+ if (pe)
+ delete pe;
+ }
+}
+
+bool kinematic_planning::RKPLBKPIECESetup::setup(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+{
+ preSetup(options);
+
+ ompl::sb::LBKPIECE1 *kpiece = new ompl::sb::LBKPIECE1(si);
+ mp = kpiece;
+
+ if (options->hasParam("range"))
+ {
+ kpiece->setRange(options->getParamDouble("range", kpiece->getRange()));
+ ROS_DEBUG("Range is set to %g", kpiece->getRange());
+ }
+
+ kpiece->setProjectionEvaluator(getProjectionEvaluator(options));
+
+ if (kpiece->getProjectionEvaluator() == NULL)
+ {
+ ROS_WARN("Adding %s failed: need to set both 'projection' and 'celldim' for %s", name.c_str(), model->groupName.c_str());
+ return false;
+ }
+ else
+ {
+ postSetup(options);
+ return true;
+ }
+}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -40,6 +40,7 @@
kinematic_planning::RKPLazyRRTSetup::RKPLazyRRTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
name = "LazyRRT";
+ priority = 2;
}
kinematic_planning::RKPLazyRRTSetup::~RKPLazyRRTSetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPPlannerSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPPlannerSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPPlannerSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -47,6 +47,7 @@
si = NULL;
svc = NULL;
smoother = NULL;
+ priority = 0;
}
kinematic_planning::RKPPlannerSetup::~RKPPlannerSetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -39,6 +39,7 @@
kinematic_planning::RKPRRTSetup::RKPRRTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
name = "RRT";
+ priority = 2;
}
kinematic_planning::RKPRRTSetup::~RKPRRTSetup(void)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp 2009-06-21 23:28:43 UTC (rev 17434)
@@ -39,6 +39,7 @@
kinematic_planning::RKPSBLSetup::RKPSBLSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
name = "SBL";
+ priority = 10;
}
kinematic_planning::RKPSBLSetup::~RKPSBLSetup(void)
Modified: pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml 2009-06-21 22:41:41 UTC (rev 17433)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml 2009-06-21 23:28:43 UTC (rev 17434)
@@ -28,7 +28,7 @@
l_wrist_flex_link
l_wrist_roll_link
planner_configs:
- RRTConfig2 SBLConfig2 KPIECEConfig2l
+ RRTConfig2 SBLConfig2 LBKPIECEConfig1 KPIECEConfig2l
right_arm:
links:
@@ -42,7 +42,7 @@
r_wrist_flex_link
r_wrist_roll_link
planner_configs:
- RRTConfig2 SBLConfig2 KPIECEConfig2r
+ RRTConfig2 SBLConfig2 LBKPIECEConfig1 KPIECEConfig2r
arms:
links:
@@ -111,4 +111,8 @@
type: KPIECE
projection: link r_wrist_roll_link
celldim: 0.1 0.1 0.1
-
\ No newline at end of file
+
+ LBKPIECEConfig1:
+ type: LBKPIECE
+ projection: 5 6
+ celldim: 0.1 0.1
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|