diff --git a/joint_state_publisher/CMakeLists.txt b/joint_state_publisher/CMakeLists.txt new file mode 100644 index 0000000..8ff1a27 --- /dev/null +++ b/joint_state_publisher/CMakeLists.txt @@ -0,0 +1,8 @@ +cmake_minimum_required(VERSION 2.8.3) +project(joint_state_publisher) + +find_package(catkin) + +catkin_python_setup() + +catkin_package() diff --git a/visualization/joint_state_publisher/joint_state_publisher b/joint_state_publisher/joint_state_publisher/joint_state_publisher similarity index 100% rename from visualization/joint_state_publisher/joint_state_publisher rename to joint_state_publisher/joint_state_publisher/joint_state_publisher diff --git a/joint_state_publisher/package.xml b/joint_state_publisher/package.xml new file mode 100644 index 0000000..bf4d1c2 --- /dev/null +++ b/joint_state_publisher/package.xml @@ -0,0 +1,22 @@ + + joint_state_publisher + 1.9.32 + + This package contains a tool for setting and publishing joint state values for a given URDF. + + David Lu!!! + David Lu!!! + BSD + http://www.ros.org/wiki/joint_state_publisher + + catkin + + rospy + wxpython + sensor_msgs + + rospy + wxpython + sensor_msgs + + diff --git a/visualization/joint_state_publisher/screenshot.png b/joint_state_publisher/screenshot.png similarity index 100% rename from visualization/joint_state_publisher/screenshot.png rename to joint_state_publisher/screenshot.png diff --git a/joint_state_publisher/setup.py b/joint_state_publisher/setup.py new file mode 100644 index 0000000..71d79df --- /dev/null +++ b/joint_state_publisher/setup.py @@ -0,0 +1,9 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup() +d['packages'] = [] +d['scripts'] = ['joint_state_publisher/joint_state_publisher'] +d['package_dir'] = {} + +setup(**d) diff --git a/srdf/CMakeLists.txt b/srdf/CMakeLists.txt deleted file mode 100644 index f2d926a..0000000 --- a/srdf/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(srdf) - -find_package(catkin REQUIRED) - -catkin_package( - INCLUDE_DIRS include -) - -install(DIRECTORY include/ - DESTINATION include) diff --git a/srdf/include/srdf/model.h b/srdf/include/srdf/model.h deleted file mode 100644 index 9d0b2be..0000000 --- a/srdf/include/srdf/model.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef SRDF_INTERFACE_MODEL_ -#define SRDF_INTERFACE_MODEL_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/srdf/mainpage.dox b/srdf/mainpage.dox deleted file mode 100644 index 233eab3..0000000 --- a/srdf/mainpage.dox +++ /dev/null @@ -1,13 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -\b srdf is a parser for SRDF (Semantic Robot Description Format) documents. -Please see http://www.ros.org/wiki/srdf for more details. - - - - -*/ diff --git a/srdf/package.xml b/srdf/package.xml deleted file mode 100644 index 365997b..0000000 --- a/srdf/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - srdf - 1.9.32 - - - - SRDF (Semantic Robot Description Format) is a representation of - semantic information about robots. - - - Ioan Sucan - Ioan Sucan BSD - - http://ros.org/wiki/srdf - - catkin - - srdfdom - tinyxml - - srdfdom - tinyxml - - diff --git a/urdf_interface/CMakeLists.txt b/urdf_interface/CMakeLists.txt deleted file mode 100644 index dfe7965..0000000 --- a/urdf_interface/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(urdf_interface) - -find_package(catkin REQUIRED COMPONENTS urdfdom) - -catkin_package( - INCLUDE_DIRS include - DEPENDS urdfdom -) - -install(DIRECTORY include/ - DESTINATION include) diff --git a/urdf_interface/include/urdf_interface/color.h b/urdf_interface/include/urdf_interface/color.h deleted file mode 100644 index 828a9b4..0000000 --- a/urdf_interface/include/urdf_interface/color.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef URDF_INTERFACE_COLOR_ -#define URDF_INTERFACE_COLOR_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/urdf_interface/include/urdf_interface/joint.h b/urdf_interface/include/urdf_interface/joint.h deleted file mode 100644 index 82ec20c..0000000 --- a/urdf_interface/include/urdf_interface/joint.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef URDF_INTERFACE_JOINT_ -#define URDF_INTERFACE_JOINT_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/urdf_interface/include/urdf_interface/link.h b/urdf_interface/include/urdf_interface/link.h deleted file mode 100644 index a32fab9..0000000 --- a/urdf_interface/include/urdf_interface/link.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef URDF_INTERFACE_LINK_ -#define URDF_INTERFACE_LINK_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/urdf_interface/include/urdf_interface/model.h b/urdf_interface/include/urdf_interface/model.h deleted file mode 100644 index 5b0ebe4..0000000 --- a/urdf_interface/include/urdf_interface/model.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef URDF_INTERFACE_MODEL_ -#define URDF_INTERFACE_MODEL_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/urdf_interface/include/urdf_interface/pose.h b/urdf_interface/include/urdf_interface/pose.h deleted file mode 100644 index 9dd19cd..0000000 --- a/urdf_interface/include/urdf_interface/pose.h +++ /dev/null @@ -1,42 +0,0 @@ -/********************************************************************* -* 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. -*********************************************************************/ - -#ifndef URDF_INTERFACE_POSE_ -#define URDF_INTERFACE_POSE_ - -#warning "Please Use #include " - -#include - -#endif diff --git a/urdf_interface/mainpage.dox b/urdf_interface/mainpage.dox deleted file mode 100644 index 9287a45..0000000 --- a/urdf_interface/mainpage.dox +++ /dev/null @@ -1,159 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -urdf::Model is a class containing robot model data structure. -Every Robot Description File (URDF) can be described as a list of Links (urdf::Model::links_) and Joints (urdf::Model::joints_). -The connection between links(nodes) and joints(edges) should define a tree (i.e. 1 parent link, 0+ children links). -\li Here is an example Robot Description Describing a Parent Link 'P', a Child Link 'C', and a Joint 'J' - @verbatim - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @endverbatim - - - -\section codeapi Code API - -The URDF parser API contains the following methods: - \li Parse and build tree from XML: urdf::Model::initXml - \li Parse and build tree from File: urdf::Model::initFile - \li Parse and build tree from String: urdf::Model::initString - \li Get Root Link: urdf::Model::getRoot - \li Get Link by name urdf::Model::getLink - \li Get all Link's urdf::Model::getLinks - \li Get Joint by name urdf::Model::getJoint - - - - - - - - -*/ diff --git a/urdf_interface/package.xml b/urdf_interface/package.xml deleted file mode 100644 index e57ab08..0000000 --- a/urdf_interface/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - urdf_interface - 1.9.32 - - This package is DEPRECATED. Please use the urdfdom dependency directly instead of this package. - - This package contains URDF C++ interface headers that define the - user API to the C++ URDF model. - - Wim Meeussen - John Hsu - Ioan Sucan - BSD - http://ros.org/wiki/urdf_interface - - catkin - - urdfdom - - urdfdom - - - - diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt deleted file mode 100644 index cf86d52..0000000 --- a/visualization/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 2.4.6) -include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) - -# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of -# directories (or patterns, but directories should suffice) that should -# be excluded from the distro. This is not the place to put things that -# should be ignored everywhere, like "build" directories; that happens in -# rosbuild/rosbuild.cmake. Here should be listed packages that aren't -# ready for inclusion in a distro. -# -# This list is combined with the list in rosbuild/rosbuild.cmake. Note -# that CMake 2.6 may be required to ensure that the two lists are combined -# properly. CMake 2.4 seems to have unpredictable scoping rules for such -# variables. -#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental) - -rosbuild_make_distribution(0.1.2) diff --git a/visualization/Makefile b/visualization/Makefile deleted file mode 100644 index a818cca..0000000 --- a/visualization/Makefile +++ /dev/null @@ -1 +0,0 @@ -include $(shell rospack find mk)/cmake_stack.mk \ No newline at end of file diff --git a/visualization/joint_state_publisher/CMakeLists.txt b/visualization/joint_state_publisher/CMakeLists.txt deleted file mode 100644 index 172441e..0000000 --- a/visualization/joint_state_publisher/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ -cmake_minimum_required(VERSION 2.4.6) -include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) - -rosbuild_init() - diff --git a/visualization/joint_state_publisher/Makefile b/visualization/joint_state_publisher/Makefile deleted file mode 100644 index b75b928..0000000 --- a/visualization/joint_state_publisher/Makefile +++ /dev/null @@ -1 +0,0 @@ -include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/visualization/joint_state_publisher/manifest.xml b/visualization/joint_state_publisher/manifest.xml deleted file mode 100644 index 5447c5d..0000000 --- a/visualization/joint_state_publisher/manifest.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - A node for publishing joint angles, either through a gui, or with - default values. - - David Lu!! - BSD - - http://ros.org/wiki/joint_state_publisher - - - - - - diff --git a/visualization/stack.xml b/visualization/stack.xml deleted file mode 100644 index c802c17..0000000 --- a/visualization/stack.xml +++ /dev/null @@ -1,11 +0,0 @@ - - This package contains a number of tools for making, viewing and using URDF models. - Maintained by David Lu!! - BSD - - http://ros.org/wiki/robot_model_visualization - - - - -