|
From: <is...@us...> - 2008-07-24 23:14:42
|
Revision: 2093
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2093&view=rev
Author: isucan
Date: 2008-07-24 23:14:51 +0000 (Thu, 24 Jul 2008)
Log Message:
-----------
changed motion planning request format and began work on new test node
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv
pkg/trunk/util/collision_space/include/collision_space/environment.h
Added Paths:
-----------
pkg/trunk/motion_planning/plan_kinematic_path/
pkg/trunk/motion_planning/plan_kinematic_path/CMakeLists.txt
pkg/trunk/motion_planning/plan_kinematic_path/Makefile
pkg/trunk/motion_planning/plan_kinematic_path/manifest.xml
pkg/trunk/motion_planning/plan_kinematic_path/src/
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-24 23:08:38 UTC (rev 2092)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-07-24 23:14:51 UTC (rev 2093)
@@ -83,7 +83,6 @@
#include <ros/node.h>
#include <std_msgs/PointCloudFloat32.h>
-#include <robot_msgs/KinematicPath.h>
#include <robot_srvs/KinematicMotionPlan.h>
#include <urdf/URDF.h>
Added: pkg/trunk/motion_planning/plan_kinematic_path/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/CMakeLists.txt (rev 0)
+++ pkg/trunk/motion_planning/plan_kinematic_path/CMakeLists.txt 2008-07-24 23:14:51 UTC (rev 2093)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(plan_kinematic_path)
+rospack_add_executable(plan_kinematic_path src/plan_kinematic_path.cpp)
Added: pkg/trunk/motion_planning/plan_kinematic_path/Makefile
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/Makefile (rev 0)
+++ pkg/trunk/motion_planning/plan_kinematic_path/Makefile 2008-07-24 23:14:51 UTC (rev 2093)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Added: pkg/trunk/motion_planning/plan_kinematic_path/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/manifest.xml (rev 0)
+++ pkg/trunk/motion_planning/plan_kinematic_path/manifest.xml 2008-07-24 23:14:51 UTC (rev 2093)
@@ -0,0 +1,9 @@
+<package>
+ <description>Test package that can plan a kinematic path</description>
+ <author>Ioan A. Sucan</author>
+ <license>BSD</license>
+ <depend package="roscpp" />
+ <depend package="robot_msgs" />
+ <depend package="robot_srvs" />
+ <depend package="xmlparam" />
+</package>
Added: pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp (rev 0)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-07-24 23:14:51 UTC (rev 2093)
@@ -0,0 +1,73 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+#include <ros/node.h>
+#include <robot_srvs/KinematicMotionPlan.h>
+
+class PlanKinematicPath : public ros::node
+{
+public:
+
+ PlanKinematicPath(void) : ros::node("plan_kinematic_path")
+ {
+ }
+
+ void runTest1(void)
+ {
+ robot_srvs::KinematicMotionPlan::request req;
+ robot_srvs::KinematicMotionPlan::response res;
+
+ if (ros::service::call("plan_kinematic_path", req, res))
+ {
+
+
+ }
+ else
+ fprintf(stderr, "Service 'plan_kinematic_path' failed\n");
+ }
+
+
+};
+
+
+int main(int argc, char **argv)
+{
+ ros::init(argc, argv);
+
+ PlanKinematicPath plan;
+ plan.runTest1();
+ plan.shutdown();
+
+ return 0;
+}
Modified: pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv
===================================================================
--- pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv 2008-07-24 23:08:38 UTC (rev 2092)
+++ pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv 2008-07-24 23:14:51 UTC (rev 2093)
@@ -2,7 +2,6 @@
robot_msgs/KinematicState start_state
robot_msgs/KinematicState goal_state
float64 allowed_time
-std_msgs/TransformQuaternion transform
std_msgs/Point3DFloat64 volumeMin
std_msgs/Point3DFloat64 volumeMax
---
Modified: pkg/trunk/util/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/util/collision_space/include/collision_space/environment.h 2008-07-24 23:08:38 UTC (rev 2092)
+++ pkg/trunk/util/collision_space/include/collision_space/environment.h 2008-07-24 23:14:51 UTC (rev 2093)
@@ -52,6 +52,7 @@
EnvironmentModel(void)
{
+ m_selfCollision = true;
}
virtual ~EnvironmentModel(void)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|