|
From: <is...@us...> - 2009-07-31 00:04:00
|
Revision: 20212
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20212&view=rev
Author: isucan
Date: 2009-07-31 00:03:50 +0000 (Fri, 31 Jul 2009)
Log Message:
-----------
proper fix for the const'ness issue
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl_planning/src/helpers/ModelBase.cpp
pkg/trunk/sandbox/3dnav_pr2/manifest.xml
pkg/trunk/world_models/collision_space/include/collision_space/environment.h
pkg/trunk/world_models/collision_space/include/collision_space/environmentBullet.h
pkg/trunk/world_models/collision_space/include/collision_space/environmentODE.h
pkg/trunk/world_models/collision_space/src/environment.cpp
pkg/trunk/world_models/collision_space/src/environmentBullet.cpp
pkg/trunk/world_models/collision_space/src/environmentODE.cpp
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ModelBase.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ModelBase.cpp 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ModelBase.cpp 2009-07-31 00:03:50 UTC (rev 20212)
@@ -57,7 +57,7 @@
{
result = new EnvironmentDescription();
result->collisionSpace = planningMonitor->getEnvironmentModel();
- result->kmodel = const_cast<planning_models::KinematicModel*>(result->collisionSpace->getRobotModel().get());
+ result->kmodel = result->collisionSpace->getRobotModel().get();
result->constraintEvaluator = &constraintEvaluator;
}
else
@@ -65,7 +65,7 @@
ROS_DEBUG("Cloning collision environment (%d total)", (int)ENVS.size() + 1);
result = new EnvironmentDescription();
result->collisionSpace = planningMonitor->getEnvironmentModel()->clone();
- result->kmodel = const_cast<planning_models::KinematicModel*>(result->collisionSpace->getRobotModel().get());
+ result->kmodel = result->collisionSpace->getRobotModel().get();
planning_environment::KinematicConstraintEvaluatorSet *kce = new planning_environment::KinematicConstraintEvaluatorSet();
kce->add(result->kmodel, constraintEvaluator.getPoseConstraints());
kce->add(result->kmodel, constraintEvaluator.getJointConstraints());
Modified: pkg/trunk/sandbox/3dnav_pr2/manifest.xml
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/manifest.xml 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/sandbox/3dnav_pr2/manifest.xml 2009-07-31 00:03:50 UTC (rev 20212)
@@ -20,6 +20,11 @@
<depend package="manipulation_msgs" />
<depend package="visualization_msgs" />
+ <!-- controllers -->
+ <depent package="pr2_default_controllers" />
+ <depent package="pr2_mechanism_controllers" />
+ <depent package="pr2_experimental_controllers" />
+
<!-- mapping -->
<depend package="laser_scan"/>
<depend package="point_cloud_assembler"/>
Modified: pkg/trunk/world_models/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/world_models/collision_space/include/collision_space/environment.h 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/include/collision_space/environment.h 2009-07-31 00:03:50 UTC (rev 20212)
@@ -111,19 +111,13 @@
bodies (multiplicative factor). The padding can be used to
increase or decrease the robot's bodies with by an
additive term */
- virtual void setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
+ virtual void setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
/** \brief Get robot scale */
- double getRobotScale(void) const
- {
- return m_robotScale;
- }
-
+ double getRobotScale(void) const;
+
/** \brief Get robot padding */
- double getRobotPadding(void) const
- {
- return m_robotPadd;
- }
+ double getRobotPadding(void) const;
/** \brief Update the positions of the geometry used in collision detection */
virtual void updateRobotModel(void) = 0;
@@ -132,12 +126,8 @@
virtual void updateAttachedBodies(void) = 0;
/** \brief Get the robot model */
- const boost::shared_ptr<const planning_models::KinematicModel>& getRobotModel(void) const
- {
- return m_robotModel;
- }
+ const boost::shared_ptr<planning_models::KinematicModel>& getRobotModel(void) const;
-
/**********************************************************************/
/* Collision Checking Routines */
/**********************************************************************/
@@ -218,7 +208,7 @@
planning_models::msg::Interface m_msg;
/** \brief Loaded robot model */
- boost::shared_ptr<const planning_models::KinematicModel> m_robotModel;
+ boost::shared_ptr<planning_models::KinematicModel> m_robotModel;
/** \brief List of objects contained in the environment */
EnvironmentObjects *m_objects;
Modified: pkg/trunk/world_models/collision_space/include/collision_space/environmentBullet.h
===================================================================
--- pkg/trunk/world_models/collision_space/include/collision_space/environmentBullet.h 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/include/collision_space/environmentBullet.h 2009-07-31 00:03:50 UTC (rev 20212)
@@ -95,7 +95,7 @@
bodies (multiplicative factor). The padding can be used to
increase or decrease the robot's bodies with by an
additive term */
- virtual void setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
+ virtual void setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
/** \brief Update the positions of the geometry used in collision detection */
virtual void updateRobotModel(void);
Modified: pkg/trunk/world_models/collision_space/include/collision_space/environmentODE.h
===================================================================
--- pkg/trunk/world_models/collision_space/include/collision_space/environmentODE.h 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/include/collision_space/environmentODE.h 2009-07-31 00:03:50 UTC (rev 20212)
@@ -85,7 +85,7 @@
bodies (multiplicative factor). The padding can be used to
increase or decrease the robot's bodies with by an
additive term */
- virtual void setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
+ virtual void setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale = 1.0, double padding = 0.0);
/** \brief Update the positions of the geometry used in collision detection */
virtual void updateRobotModel(void);
Modified: pkg/trunk/world_models/collision_space/src/environment.cpp
===================================================================
--- pkg/trunk/world_models/collision_space/src/environment.cpp 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/src/environment.cpp 2009-07-31 00:03:50 UTC (rev 20212)
@@ -51,8 +51,23 @@
return m_objects;
}
-void collision_space::EnvironmentModel::setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
+const boost::shared_ptr<planning_models::KinematicModel>& collision_space::EnvironmentModel::getRobotModel(void) const
{
+ return m_robotModel;
+}
+
+double collision_space::EnvironmentModel::getRobotScale(void) const
+{
+ return m_robotScale;
+}
+
+double collision_space::EnvironmentModel::getRobotPadding(void) const
+{
+ return m_robotPadd;
+}
+
+void collision_space::EnvironmentModel::setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
+{
m_robotModel = model;
m_collisionLinks = links;
m_selfCollisionTest.resize(links.size());
Modified: pkg/trunk/world_models/collision_space/src/environmentBullet.cpp
===================================================================
--- pkg/trunk/world_models/collision_space/src/environmentBullet.cpp 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/src/environmentBullet.cpp 2009-07-31 00:03:50 UTC (rev 20212)
@@ -59,7 +59,7 @@
delete m_config; */
}
-void collision_space::EnvironmentModelBullet::setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
+void collision_space::EnvironmentModelBullet::setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
{
collision_space::EnvironmentModel::setRobotModel(model, links, scale, padding);
m_modelGeom.scale = scale;
Modified: pkg/trunk/world_models/collision_space/src/environmentODE.cpp
===================================================================
--- pkg/trunk/world_models/collision_space/src/environmentODE.cpp 2009-07-31 00:00:17 UTC (rev 20211)
+++ pkg/trunk/world_models/collision_space/src/environmentODE.cpp 2009-07-31 00:03:50 UTC (rev 20212)
@@ -100,7 +100,7 @@
delete it->second;
}
-void collision_space::EnvironmentModelODE::setRobotModel(const boost::shared_ptr<const planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
+void collision_space::EnvironmentModelODE::setRobotModel(const boost::shared_ptr<planning_models::KinematicModel> &model, const std::vector<std::string> &links, double scale, double padding)
{
collision_space::EnvironmentModel::setRobotModel(model, links, scale, padding);
createODERobotModel();
@@ -781,7 +781,7 @@
env->m_verbose = m_verbose;
env->m_robotScale = m_robotScale;
env->m_robotPadd = m_robotPadd;
- env->m_robotModel = boost::shared_ptr<const planning_models::KinematicModel>(m_robotModel->clone());
+ env->m_robotModel = boost::shared_ptr<planning_models::KinematicModel>(m_robotModel->clone());
env->createODERobotModel();
for (unsigned int j = 0 ; j < m_modelGeom.linkGeom.size() ; ++j)
env->m_modelGeom.linkGeom[j]->enabled = m_modelGeom.linkGeom[j]->enabled;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|