|
From: <is...@us...> - 2008-08-21 01:05:25
|
Revision: 3394
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3394&view=rev
Author: isucan
Date: 2008-08-21 01:05:27 +0000 (Thu, 21 Aug 2008)
Log Message:
-----------
some more (hopefully all) files I wrote up to now have my name in them ...
Modified Paths:
--------------
pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
pkg/trunk/motion_planning/collision_space/test/test_util.cpp
pkg/trunk/motion_planning/kinematic_planning/include/SpaceInformationXMLModel.h
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/environment2D.h
pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/grid.cpp
pkg/trunk/motion_planning/ompl/code/ompl/base/General.h
pkg/trunk/motion_planning/ompl/code/ompl/base/Planner.h
pkg/trunk/motion_planning/ompl/code/ompl/base/SpaceInformation.h
pkg/trunk/motion_planning/ompl/code/ompl/base/util/random.h
pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/random.cpp
pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp
pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h
pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h
pkg/trunk/motion_planning/ompl/code/ompl/datastructures/Grid.h
pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighbors.h
pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsLinear.h
pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsSqrtApprox.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/KinematicPathSmoother.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/SBL.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/KinematicPathSmoother.cpp
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/motion_planning/planning_models/include/planning_models/kinematic.h
pkg/trunk/motion_planning/planning_models/src/planning_models/kinematic.cpp
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp
pkg/trunk/motion_planning/test_collision_space/src/test_kinematic_ode.cpp
pkg/trunk/nav/fake_localization/fake_localization.cpp
pkg/trunk/robot_descriptions/wg_robot_description_parser/include/urdf/URDF.h
pkg/trunk/robot_descriptions/wg_robot_description_parser/run_valgrind.py
pkg/trunk/robot_descriptions/wg_robot_description_parser/src/URDF.cpp
pkg/trunk/robot_descriptions/wg_robot_description_parser/src/merge.cpp
pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parse.cpp
pkg/trunk/robot_descriptions/wg_robot_description_parser/test/test_cpp_parser.cpp
pkg/trunk/util/math_utils/include/math_utils/MathExpression.h
pkg/trunk/util/math_utils/src/MathExpression.cpp
pkg/trunk/util/random_utils/include/random_utils/random_utils.h
pkg/trunk/util/random_utils/src/random_utils.cpp
pkg/trunk/util/rosTF/src/viewTF.cpp
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan, Matei Ciocarlie */
+
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef COLLISION_SPACE_UTIL_
#define COLLISION_SPACE_UTIL_
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <collision_space/environment.h>
unsigned int collision_space::EnvironmentModel::addRobotModel(planning_models::KinematicModel *model)
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <collision_space/environmentODE.h>
void collision_space::EnvironmentModelODE::freeMemory(void)
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan, Matei Ciocarlie */
+
#include <collision_space/environmentOctree.h>
unsigned int collision_space::EnvironmentModelOctree::addRobotModel(planning_models::KinematicModel *model)
Modified: pkg/trunk/motion_planning/collision_space/test/test_util.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/test/test_util.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/collision_space/test/test_util.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <collision_space/util.h>
#include <gtest/gtest.h>
Modified: pkg/trunk/motion_planning/kinematic_planning/include/SpaceInformationXMLModel.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/SpaceInformationXMLModel.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/kinematic_planning/include/SpaceInformationXMLModel.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
#include <planning_models/kinematic.h>
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
/**
@mainpage
Modified: pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/environment2D.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/environment2D.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/environment2D.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,11 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
+#ifndef ENVIDONMENT_2D_
+#define ENVIDONMENT_2D_
+
#include <fstream>
#include <vector>
#include <string>
@@ -113,3 +118,5 @@
out << std::endl;
}
}
+
+#endif
Modified: pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/grid.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/grid.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/examples/samplingbased/kinematic/grid/grid.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h"
#include "ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h"
#include "environment2D.h"
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/General.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/General.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/General.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_BASE_GENERAL_
#define OMPL_BASE_GENERAL_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/Planner.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/Planner.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/Planner.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_BASE_MOTION_PLANNER_
#define OMPL_BASE_MOTION_PLANNER_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/SpaceInformation.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/SpaceInformation.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/SpaceInformation.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_BASE_SPACE_INFORMATION_
#define OMPL_BASE_SPACE_INFORMATION_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/random.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/random.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/random.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,6 +1,8 @@
#ifndef OMPL_RANDOM_
#define OMPL_RANDOM_
+/** \Author Ioan Sucan (adaptation from ROS) */
+
namespace ompl
{
namespace random_utils
@@ -35,6 +37,10 @@
double bounded_gaussian(double mean, double stddev, double max_stddev);
double bounded_gaussian(rngState *state, double mean, double stddev,
double max_stddev);
+
+ /** Random quaternion generator */
+ void quaternion(double value[4]);
+ void quaternion(rngState* state, double value[4]);
}
}
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/random.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/random.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/random.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,3 +1,39 @@
+/*********************************************************************
+* 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 (adaptation from ROS) */
+
#include <cstdio>
#include <cstdlib>
#include <cmath>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,3 +1,39 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+/** This file is taken from ROS, adaptations by Ioan Sucan */
+
#include "ompl/base/util/time.h"
#include <cmath>
#include <time.h>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -36,6 +36,8 @@
#ifndef OMPL_TIME_
#define OMPL_TIME_
+/** This file is taken from ROS, adaptations by Ioan Sucan */
+
#include <iostream>
#include <cmath>
#include "ompl/base/util/types.h"
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** This file is taken from ROS */
+
#ifndef OMPL_TYPES_
#define OMPL_TYPES_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/datastructures/Grid.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/datastructures/Grid.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/datastructures/Grid.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_DATASTRUCTURES_GRID_
#define OMPL_DATASTRUCTURES_GRID_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighbors.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighbors.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighbors.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_
#define OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsLinear.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsLinear.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsLinear.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_LINEAR_
#define OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_LINEAR_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsSqrtApprox.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsSqrtApprox.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/datastructures/NearestNeighborsSqrtApprox.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_SQRT_APPROX_
#define OMPL_DATASTRUCTURES_NEAREST_NEIGHBORS_SQRT_APPROX_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/KinematicPathSmoother.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/KinematicPathSmoother.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/KinematicPathSmoother.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_KINEMATIC_PATH_SMOOTHER_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_KINEMATIC_PATH_SMOOTHER_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_SPACE_INFORMATION_KINEMATIC_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_SPACE_INFORMATION_KINEMATIC_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_LAZY_RRT_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_LAZY_RRT_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_RRT_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_RRT_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h"
#include <cassert>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h"
bool ompl::RRT::solve(double solveTime)
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/SBL.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/SBL.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/SBL.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_SBL_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_SBL_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/extension/sbl/SBL.h"
bool ompl::SBL::solve(double solveTime)
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/KinematicPathSmoother.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/KinematicPathSmoother.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/KinematicPathSmoother.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/KinematicPathSmoother.h"
#include "ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h"
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h"
#include <math_utils/angles.h>
#include <valarray>
Modified: pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,11 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+
+/** \Author Ioan Sucan */
+
+/** This is a simple program for requesting a motion plan */
+
#include <ros/node.h>
#include <ros/time.h>
#include <robot_srvs/KinematicPlanState.h>
@@ -44,11 +49,11 @@
PlanKinematicPath(void) : ros::node("plan_kinematic_path")
{
- advertise<robot_msgs::NamedKinematicPath>("display_kinematic_path");
+ advertise<robot_msgs::NamedKinematicPath>("display_kinematic_path", 1);
m_basePos[0] = m_basePos[1] = m_basePos[2] = 0.0;
m_haveBasePos = false;
- subscribe("localizedpose", m_localizedPose, &PlanKinematicPath::localizedPoseCallback);
+ subscribe("localizedpose", m_localizedPose, &PlanKinematicPath::localizedPoseCallback, 1);
}
bool haveBasePos(void) const
Modified: pkg/trunk/motion_planning/planning_models/include/planning_models/kinematic.h
===================================================================
--- pkg/trunk/motion_planning/planning_models/include/planning_models/kinematic.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/planning_models/include/planning_models/kinematic.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef KINEMATIC_ROBOT_MODEL_
#define KINEMATIC_ROBOT_MODEL_
Modified: pkg/trunk/motion_planning/planning_models/src/planning_models/kinematic.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_models/src/planning_models/kinematic.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/planning_models/src/planning_models/kinematic.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <planning_models/kinematic.h>
#include <algorithm>
#include <cmath>
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
/**
@mainpage
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
/**
@mainpage
Modified: pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
/**
@mainpage
Modified: pkg/trunk/motion_planning/test_collision_space/src/test_kinematic_ode.cpp
===================================================================
--- pkg/trunk/motion_planning/test_collision_space/src/test_kinematic_ode.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/motion_planning/test_collision_space/src/test_kinematic_ode.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,11 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
+/** Test program for displaying and testing ODE collision spaces and
+ kinematic models */
+
#include <collision_space/environmentODE.h>
#include <display_ode/displayODE.h>
#include <algorithm>
Modified: pkg/trunk/nav/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
/**
@mainpage
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/include/urdf/URDF.h
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/include/urdf/URDF.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/include/urdf/URDF.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef URDF_PARSER_
#define URDF_PARSER_
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/run_valgrind.py
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/run_valgrind.py 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/run_valgrind.py 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,4 +1,34 @@
#!/usr/bin/env python
+
+# 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, Inc. 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
+
from subprocess import Popen, PIPE
import string
import re
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/src/URDF.cpp
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/src/URDF.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/src/URDF.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <urdf/URDF.h>
#include <math_utils/MathExpression.h>
#include <string_utils/string_utils.h>
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/src/merge.cpp
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/src/merge.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/src/merge.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <tinyxml/tinyxml.h>
#include <cassert>
#include <vector>
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parse.cpp
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parse.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parse.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,3 +1,39 @@
+/*********************************************************************
+ * 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 <urdf/URDF.h>
#include <cstdio>
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/test/test_cpp_parser.cpp
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/test/test_cpp_parser.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/test/test_cpp_parser.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan, Stu Glassner */
+
#include <urdf/URDF.h>
#include <urdf/parser.h>
#include <gtest/gtest.h>
Modified: pkg/trunk/util/math_utils/include/math_utils/MathExpression.h
===================================================================
--- pkg/trunk/util/math_utils/include/math_utils/MathExpression.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/util/math_utils/include/math_utils/MathExpression.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#ifndef MATH_EXPRESSION_
#define MATH_EXPRESSION_
Modified: pkg/trunk/util/math_utils/src/MathExpression.cpp
===================================================================
--- pkg/trunk/util/math_utils/src/MathExpression.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/util/math_utils/src/MathExpression.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include "math_utils/MathExpression.h"
#include <cstring>
#include <cmath>
Modified: pkg/trunk/util/random_utils/include/random_utils/random_utils.h
===================================================================
--- pkg/trunk/util/random_utils/include/random_utils/random_utils.h 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/util/random_utils/include/random_utils/random_utils.h 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,3 +1,39 @@
+/*********************************************************************
+* 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 Morgan Quigley, Ioan Sucan */
+
#ifndef RANDOM_UTILS_H
#define RANDOM_UTILS_H
Modified: pkg/trunk/util/random_utils/src/random_utils.cpp
===================================================================
--- pkg/trunk/util/random_utils/src/random_utils.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/util/random_utils/src/random_utils.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -1,3 +1,39 @@
+/*********************************************************************
+* 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 Morgan Quigley, Ioan Sucan */
+
#include <cstdio>
#include <cstdlib>
#include <cmath>
Modified: pkg/trunk/util/rosTF/src/viewTF.cpp
===================================================================
--- pkg/trunk/util/rosTF/src/viewTF.cpp 2008-08-21 00:56:06 UTC (rev 3393)
+++ pkg/trunk/util/rosTF/src/viewTF.cpp 2008-08-21 01:05:27 UTC (rev 3394)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+/** \Author Ioan Sucan */
+
#include <ros/node.h>
#include <ros/time.h>
#include <rosTF/rosTF.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|