|
From: <tpr...@us...> - 2009-01-07 00:18:51
|
Revision: 8928
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8928&view=rev
Author: tpratkanis
Date: 2009-01-07 00:18:47 +0000 (Wed, 07 Jan 2009)
Log Message:
-----------
Move planning_node_util to robot_model in the world_models directory.
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/manifest.xml
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
pkg/trunk/world_models/robot_model/CMakeLists.txt
pkg/trunk/world_models/robot_model/include/robot_model/cnode.h
pkg/trunk/world_models/robot_model/include/robot_model/knode.h
pkg/trunk/world_models/world_3d_map/manifest.xml
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Added Paths:
-----------
pkg/trunk/world_models/robot_model/
pkg/trunk/world_models/robot_model/include/robot_model/
Removed Paths:
-------------
pkg/trunk/motion_planning/planning_node_util/
Modified: pkg/trunk/motion_planning/kinematic_planning/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/manifest.xml 2009-01-07 00:10:40 UTC (rev 8927)
+++ pkg/trunk/motion_planning/kinematic_planning/manifest.xml 2009-01-07 00:18:47 UTC (rev 8928)
@@ -8,7 +8,7 @@
<depend package="wg_robot_description" />
<depend package="robot_msgs" />
<depend package="robot_srvs" />
- <depend package="planning_node_util" />
+ <depend package="robot_model" />
<depend package="ompl" />
<depend package="profiling_utils" />
<depend package="string_utils" />
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2009-01-07 00:10:40 UTC (rev 8927)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2009-01-07 00:18:47 UTC (rev 8928)
@@ -130,7 +130,7 @@
**/
-#include <planning_node_util/cnode.h>
+#include <robot_model/cnode.h>
#include <std_msgs/String.h>
#include "RKPModel.h"
@@ -140,12 +140,12 @@
#include <robot_srvs/NamedKinematicPlanState.h>
class KinematicPlanning : public ros::node,
- public planning_node_util::NodeCollisionModel
+ public robot_model::NodeCollisionModel
{
public:
KinematicPlanning(const std::string &robot_model) : ros::node("kinematic_planning"),
- planning_node_util::NodeCollisionModel(dynamic_cast<ros::node*>(this),
+ robot_model::NodeCollisionModel(dynamic_cast<ros::node*>(this),
robot_model)
{
advertise_service("plan_kinematic_path_state", &KinematicPlanning::planToState);
@@ -345,7 +345,7 @@
virtual void setRobotDescription(robot_desc::URDF *file)
{
- planning_node_util::NodeCollisionModel::setRobotDescription(file);
+ robot_model::NodeCollisionModel::setRobotDescription(file);
defaultPosition();
printf("=======================================\n");
@@ -400,6 +400,7 @@
const robot_desc::URDF::Map &data = group->data;
options = data.getMapTagValues("planning", "RRT");
}
+
model->addRRT(options);
Modified: pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp 2009-01-07 00:10:40 UTC (rev 8927)
+++ pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp 2009-01-07 00:18:47 UTC (rev 8928)
@@ -88,7 +88,7 @@
**/
-#include <planning_node_util/cnode.h>
+#include <robot_model/cnode.h>
#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
#include <robot_srvs/ValidateKinematicPath.h>
@@ -101,7 +101,7 @@
#include <map>
class MotionValidator : public ros::node,
- public planning_node_util::NodeCollisionModel
+ public robot_model::NodeCollisionModel
{
public:
@@ -127,7 +127,7 @@
};
MotionValidator(const std::string &robot_model) : ros::node("motion_validator"),
- planning_node_util::NodeCollisionModel(dynamic_cast<ros::node*>(this),
+ robot_model::NodeCollisionModel(dynamic_cast<ros::node*>(this),
robot_model)
{
advertise_service("validate_path", &MotionValidator::validatePath);
@@ -205,7 +205,7 @@
virtual void setRobotDescription(robot_desc::URDF *file)
{
- planning_node_util::NodeCollisionModel::setRobotDescription(file);
+ robot_model::NodeCollisionModel::setRobotDescription(file);
printf("=======================================\n");
m_kmodel->printModelInfo();
Modified: pkg/trunk/world_models/robot_model/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/CMakeLists.txt 2009-01-06 02:42:45 UTC (rev 8864)
+++ pkg/trunk/world_models/robot_model/CMakeLists.txt 2009-01-07 00:18:47 UTC (rev 8928)
@@ -1,3 +1,3 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-rospack(planning_node_util)
+rospack(robot_model)
Modified: pkg/trunk/world_models/robot_model/include/robot_model/cnode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2009-01-06 22:09:07 UTC (rev 8914)
+++ pkg/trunk/world_models/robot_model/include/robot_model/cnode.h 2009-01-07 00:18:47 UTC (rev 8928)
@@ -34,12 +34,12 @@
/** \author Ioan Sucan */
-#include <planning_node_util/knode.h>
+#include <robot_model/knode.h>
#include <std_msgs/PointCloud.h>
#include <collision_space/environmentODE.h>
/** Main namespace */
-namespace planning_node_util
+namespace robot_model
{
/**
Modified: pkg/trunk/world_models/robot_model/include/robot_model/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2009-01-06 22:09:07 UTC (rev 8914)
+++ pkg/trunk/world_models/robot_model/include/robot_model/knode.h 2009-01-07 00:18:47 UTC (rev 8928)
@@ -54,7 +54,7 @@
#include <robot_msgs/MechanismState.h>
/** Main namespace */
-namespace planning_node_util
+namespace robot_model
{
/**
@b NodeRobotModel is a class that is also of a given robot model and
@@ -88,7 +88,7 @@
public:
- NodeRobotModel(ros::node *node, const std::string &robot_model) : m_tf(*node, true, 1000000000ULL)
+ NodeRobotModel(ros::node *node, const std::string &robot_model_name) : m_tf(*node, true, 1000000000ULL)
{
m_tf.setExtrapolationLimit(ros::Duration().fromSec(10));
m_urdf = NULL;
@@ -98,7 +98,7 @@
m_robotStateSimple = NULL;
m_node = node;
m_basePos[0] = m_basePos[1] = m_basePos[2] = 0.0;
- m_robotModelName = robot_model;
+ m_robotModelName = robot_model_name;
m_haveState = false;
m_haveMechanismState = false;
m_haveBasePos = false;
Modified: pkg/trunk/world_models/world_3d_map/manifest.xml
===================================================================
--- pkg/trunk/world_models/world_3d_map/manifest.xml 2009-01-07 00:10:40 UTC (rev 8927)
+++ pkg/trunk/world_models/world_3d_map/manifest.xml 2009-01-07 00:18:47 UTC (rev 8928)
@@ -12,5 +12,5 @@
<depend package="wg_robot_description_parser" />
<depend package="planning_models" />
<depend package="collision_space" />
-<depend package="planning_node_util" />
+<depend package="robot_model" />
</package>
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2009-01-07 00:10:40 UTC (rev 8927)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2009-01-07 00:18:47 UTC (rev 8928)
@@ -102,7 +102,7 @@
- @b "world_3d_map/verbosity_level" : @b [int] sets the verbosity level (default 1)
**/
-#include <planning_node_util/knode.h>
+#include <robot_model/knode.h>
#include <rosthread/member_thread.h>
#include <rosthread/mutex.h>
@@ -120,12 +120,12 @@
#include <cmath>
class World3DMap : public ros::node,
- public planning_node_util::NodeRobotModel
+ public robot_model::NodeRobotModel
{
public:
- World3DMap(const std::string &robot_model) : ros::node("world_3d_map"),
- planning_node_util::NodeRobotModel(dynamic_cast<ros::node*>(this), robot_model)
+ World3DMap(const std::string &robot_model_name) : ros::node("world_3d_map"),
+ robot_model::NodeRobotModel(dynamic_cast<ros::node*>(this), robot_model_name)
{
advertise<std_msgs::PointCloud>("world_3d_map", 1);
@@ -163,7 +163,7 @@
virtual void setRobotDescription(robot_desc::URDF *file)
{
- planning_node_util::NodeRobotModel::setRobotDescription(file);
+ robot_model::NodeRobotModel::setRobotDescription(file);
addSelfSeeBodies();
}
@@ -188,7 +188,7 @@
return;
}
//m_robotState->print();
- planning_node_util::NodeRobotModel::stateUpdate();
+ robot_model::NodeRobotModel::stateUpdate();
if (m_kmodel)
m_kmodel->computeTransforms(m_robotState->getParams());
if (m_kmodelSimple)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|