diff --git a/README.md b/README.md index ef6d2698..15901339 100644 --- a/README.md +++ b/README.md @@ -16,3 +16,5 @@ More information is available at [`ros/robot_model#195`](https://github.com/ros/ * [`ros/joint_state_publisher`](https://github.com/ros/joint_state_publisher) * `kdl_parser` and `kdl_parser_py` * [`ros/kdl_parser`](https://github.com/ros/kdl_parser) +* `urdf` and `urdf_parser_plugin` + * [`ros/urdf`](https://github.com/ros/urdf) diff --git a/urdf/CHANGELOG.rst b/urdf/CHANGELOG.rst deleted file mode 100644 index 023a4d87..00000000 --- a/urdf/CHANGELOG.rst +++ /dev/null @@ -1,118 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package urdf -^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.12.11 (2017-06-27) --------------------- -* Shared ptr yakkety (`#207 `_) - * Forward declare urdf::Model when urdfdom version is > 0.4 - * Add test for upcasting from urdf::ModelSharedPtr to urdf::ModelInterfaceSharedPtr -* Contributors: Shane Loretz - -1.12.10 (2017-06-24) --------------------- -* Change urdf::Model to use std::shared_ptrs in urdfdom > v0.4 (`#206 `_) -* Contributors: Dave Coleman - -1.12.9 (2017-04-26) -------------------- - -1.12.8 (2017-03-27) -------------------- -* Allow supplying NodeHandle for initParam (`#168 `_) - * Allow supplying NodeHandle for initParam using new function. - * fixed missing return statement in previous commit. -* add Chris and Shane as maintainers (`#184 `_) -* fix missed mandatory -std=c++11 flag (`#181 `_) - collada_parser,kdl_parser,urdf: add c++11 flag, - collada_parser: replace typeof with ansi __typeof\_\_ - builded/tested on gentoo - Thanks den4ix for the contribution! -* Contributors: Denis Romanchuk, Piyush Khandelwal, William Woodall - -1.12.7 (2017-01-26) -------------------- - -1.12.6 (2017-01-04) -------------------- -* Addressed gcc6 build error in the urdf package, forward port of `#156 `_ (`#173 `_) -* Now using ``urdf::*ShredPtr`` instead of ``boost::shared_ptr`` (`#144 `_) -* Contributors: Jochen Sprickerhof, William Woodall - -1.12.5 (2016-10-27) -------------------- -* Added urdf_compatibility.h header to define SharedPtr types (`#160 `_) - This provides portability for downstream packages allowing them to use urdfdom 0.3 or 0.4. -* urdf: Explicitly cast shared_ptr to bool in unit test. (`#158 `_) -* Add smart ptr typedefs (`#153 `_) -* Addressed gcc6 build error in urdf which was related to use of the isystem flag (`#157 `_) -* Remove unneeded dependency on libpcrecpp (`#155 `_) -* Contributors: Bence Magyar, Jochen Sprickerhof, Lukas Bulwahn, Maarten de Vries, Robert Haschke - -1.12.4 (2016-08-23) -------------------- - -1.12.3 (2016-06-10) -------------------- - -1.12.2 (2016-04-12) -------------------- - -1.12.1 (2016-04-10) -------------------- - -1.11.8 (2015-09-11) -------------------- -* Removed pcre hack for newer released collada-dom. -* Fixed link order of libpcrecpp. -* Contributors: Kei Okada - -1.11.7 (2015-04-22) -------------------- -* Removed the exporting of Boost and pcre as they are not used in the headers, and added TinyXML because it is. -* Fixed a bug with pcrecpp on Ubuntu > 13.04. -* Contributors: Kei Okada, William Woodall - -1.11.6 (2014-11-30) -------------------- -* Add install for static libs needed for Android cross-compilation -* Contributors: Gary Servin - -1.11.5 (2014-07-24) -------------------- - -1.11.4 (2014-07-07) -------------------- -* moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 -* Contributors: Tully Foote - -1.11.3 (2014-06-24) -------------------- -* fix urdfdom_headers find_package re `ros/rosdistro#4633 `_ -* Contributors: Tully Foote - -1.11.2 (2014-03-22) -------------------- - -1.11.1 (2014-03-20) -------------------- - -1.11.0 (2014-02-21) -------------------- -* fix urdf files for test -* fix test at urdf -* Contributors: YoheiKakiuchi - -1.10.18 (2013-12-04) --------------------- -* add DEPENDS for kdl_parser -* Contributors: Ioan Sucan - -1.10.16 (2013-11-18) --------------------- -* check for CATKIN_ENABLE_TESTING -* fix for using collada_parser_plugin - -1.10.15 (2013-08-17) --------------------- -* fix `#30 `_ diff --git a/urdf/CMakeLists.txt b/urdf/CMakeLists.txt deleted file mode 100644 index 5c9c7cd7..00000000 --- a/urdf/CMakeLists.txt +++ /dev/null @@ -1,69 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(urdf) - -find_package(Boost REQUIRED thread) -find_package(urdfdom REQUIRED) -find_package(urdfdom_headers REQUIRED) -find_package(catkin REQUIRED COMPONENTS - urdf_parser_plugin pluginlib rosconsole_bridge roscpp cmake_modules) - - -find_package(TinyXML REQUIRED) - -# Find version components -if(NOT urdfdom_headers_VERSION) -set(urdfdom_headers_VERSION "0.0.0") -endif() -string(REGEX REPLACE "^([0-9]+).*" "\\1" URDFDOM_HEADERS_MAJOR_VERSION "${urdfdom_headers_VERSION}") -string(REGEX REPLACE "^[0-9]+\\.([0-9]+).*" "\\1" URDFDOM_HEADERS_MINOR_VERSION "${urdfdom_headers_VERSION}") -string(REGEX REPLACE "^[0-9]+\\.[0-9]+\\.([0-9]+).*" "\\1" URDFDOM_HEADERS_REVISION_VERSION "${urdfdom_headers_VERSION}") -set(generated_compat_header "${CATKIN_DEVEL_PREFIX}/include/${PROJECT_NAME}/urdfdom_compatibility.h") -include_directories("${CATKIN_DEVEL_PREFIX}/include") -configure_file(urdfdom_compatibility.h.in "${generated_compat_header}" @ONLY) - -add_compile_options(-std=c++11) - -catkin_package( - LIBRARIES ${PROJECT_NAME} - INCLUDE_DIRS include ${CATKIN_DEVEL_PREFIX}/include - CATKIN_DEPENDS rosconsole_bridge roscpp - DEPENDS urdfdom_headers urdfdom Boost TinyXML -) -install(FILES ${generated_compat_header} DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) - -include_directories( - include - ${Boost_INCLUDE_DIR} - ${catkin_INCLUDE_DIRS} - ${urdfdom_INCLUDE_DIRS} - ${urdfdom_headers_INCLUDE_DIRS} - ${TinyXML_INCLUDE_DIRS} - ) - -link_directories(${Boost_LIBRARY_DIRS} ${catkin_LIBRARY_DIRS}) - -add_library(${PROJECT_NAME} src/model.cpp src/rosconsole_bridge.cpp) -target_link_libraries(${PROJECT_NAME} ${TinyXML_LIBRARIES} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES}) - -if(APPLE) - set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "-undefined dynamic_lookup") -endif(APPLE) - -if(CATKIN_ENABLE_TESTING) - find_package(catkin REQUIRED COMPONENTS rostest) - add_rostest_gtest(test_urdf_parser test/test_robot_model_parser.launch test/test_robot_model_parser.cpp) - target_link_libraries(test_urdf_parser ${PROJECT_NAME}) - - catkin_add_gtest(urdfdom_compatibility_test test/urdfdom_compatibility.cpp) -endif() - -# no idea how CATKIN does this -# rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/test_robot_model_parser.launch) - -install(TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) diff --git a/urdf/include/urdf/model.h b/urdf/include/urdf/model.h deleted file mode 100644 index 6d32fc36..00000000 --- a/urdf/include/urdf/model.h +++ /dev/null @@ -1,72 +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. -*********************************************************************/ - -/* Author: Wim Meeussen */ - -#ifndef URDF_MODEL_H -#define URDF_MODEL_H - -#include -#include -#include -#include -#include -#include -#include -#include - -namespace urdf{ - -class Model: public ModelInterface -{ -public: - /// \brief Load Model from TiXMLElement - bool initXml(TiXmlElement *xml); - /// \brief Load Model from TiXMLDocument - bool initXml(TiXmlDocument *xml); - /// \brief Load Model given a filename - bool initFile(const std::string& filename); - /// \brief Load Model given the name of a parameter on the parameter server - bool initParam(const std::string& param); - /// \brief Load Model given the name of a parameter on the parameter server using provided nodehandle - bool initParamWithNodeHandle(const std::string& param, const ros::NodeHandle& nh = ros::NodeHandle()); - /// \brief Load Model from a XML-string - bool initString(const std::string& xmlstring); -}; - -// shared_ptr declarations moved to urdf/urdfdom_compatibility.h to allow for std::shared_ptrs in latest version - -} - -#endif diff --git a/urdf/mainpage.dox b/urdf/mainpage.dox deleted file mode 100644 index 9287a452..00000000 --- a/urdf/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/package.xml b/urdf/package.xml deleted file mode 100644 index e4b190dc..00000000 --- a/urdf/package.xml +++ /dev/null @@ -1,44 +0,0 @@ - - urdf - 1.12.11 - - This package contains a C++ parser for the Unified Robot Description - Format (URDF), which is an XML format for representing a robot model. - The code API of the parser has been through our review process and will remain - backwards compatible in future releases. - - - Ioan Sucan - Jackie Kay - Chris Lalancette - Shane Loretz - - BSD - - http://ros.org/wiki/urdf - https://github.com/ros/robot_model - https://github.com/ros/robot_model/issues - - catkin - - liburdfdom-dev - liburdfdom-headers-dev - rosconsole_bridge - roscpp - urdf_parser_plugin - pluginlib - cmake_modules - tinyxml - - liburdfdom-dev - rosconsole_bridge - roscpp - pluginlib - tinyxml - - tinyxml - liburdfdom-headers-dev - - rostest - - diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp deleted file mode 100644 index 03cc774f..00000000 --- a/urdf/src/model.cpp +++ /dev/null @@ -1,193 +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. -*********************************************************************/ - -/* Author: Wim Meeussen */ - -#include "urdf/model.h" - -/* we include the default parser for plain URDF files; - other parsers are loaded via plugins (if available) */ -#include -#include -#include - -#include -#include -#include - -#include -#include -#include - -namespace urdf{ - -static bool IsColladaData(const std::string& data) -{ - return data.find(" > PARSER_PLUGIN_LOADER; - boost::mutex::scoped_lock _(PARSER_PLUGIN_LOCK); - - try - { - if (!PARSER_PLUGIN_LOADER) - PARSER_PLUGIN_LOADER.reset(new pluginlib::ClassLoader("urdf_parser_plugin", "urdf::URDFParser")); - const std::vector &classes = PARSER_PLUGIN_LOADER->getDeclaredClasses(); - bool found = false; - for (std::size_t i = 0 ; i < classes.size() ; ++i) - if (classes[i].find("urdf/ColladaURDFParser") != std::string::npos) - { - boost::shared_ptr instance = PARSER_PLUGIN_LOADER->createInstance(classes[i]); - if (instance) - model = instance->parse(xml_string); - found = true; - break; - } - if (!found) - ROS_ERROR_STREAM("No URDF parser plugin found for Collada files. Did you install the corresponding package?"); - } - catch(pluginlib::PluginlibException& ex) - { - ROS_ERROR_STREAM("Exception while creating planning plugin loader " << ex.what() << ". Will not parse Collada file."); - } - } - else { - ROS_DEBUG("Parsing robot urdf xml string"); - model = parseURDF(xml_string); - } - - // copy data from model into this object - if (model){ - this->links_ = model->links_; - this->joints_ = model->joints_; - this->materials_ = model->materials_; - this->name_ = model->name_; - this->root_link_ = model->root_link_; - return true; - } - return false; -} - - - -}// namespace diff --git a/urdf/src/rosconsole_bridge.cpp b/urdf/src/rosconsole_bridge.cpp deleted file mode 100644 index b1cd3945..00000000 --- a/urdf/src/rosconsole_bridge.cpp +++ /dev/null @@ -1,38 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2011, 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 - -REGISTER_ROSCONSOLE_BRIDGE; - diff --git a/urdf/test/fail_pr2_desc_bracket.urdf b/urdf/test/fail_pr2_desc_bracket.urdf deleted file mode 100644 index d0caaa81..00000000 --- a/urdf/test/fail_pr2_desc_bracket.urdf +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_double.urdf b/urdf/test/fail_pr2_desc_double.urdf deleted file mode 100644 index 10bbd4c7..00000000 --- a/urdf/test/fail_pr2_desc_double.urdf +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_double_joint.urdf b/urdf/test/fail_pr2_desc_double_joint.urdf deleted file mode 100644 index 2974a7aa..00000000 --- a/urdf/test/fail_pr2_desc_double_joint.urdf +++ /dev/null @@ -1,38 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_loop.urdf b/urdf/test/fail_pr2_desc_loop.urdf deleted file mode 100644 index ab210245..00000000 --- a/urdf/test/fail_pr2_desc_loop.urdf +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_no_filename_in_mesh.urdf b/urdf/test/fail_pr2_desc_no_filename_in_mesh.urdf deleted file mode 100644 index 88d75b39..00000000 --- a/urdf/test/fail_pr2_desc_no_filename_in_mesh.urdf +++ /dev/null @@ -1,3377 +0,0 @@ - - - - - - - - - - - - - - - - - - - - true - 1000.0 - - - - - - true - 1000.0 - - - - - - true - 1.0 - 5 - -10.0 - 1.0 - 10.0 - 1200000.0 - diagnostic - battery_state - self_test - - - - - true - 1000.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - fl_caster_l_wheel_link_geom - 100.0 - - true - 100.0 - fl_caster_l_wheel_bumper - - - - - - - - - - - - 75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - fl_caster_r_wheel_link_geom - 100.0 - - true - 100.0 - fl_caster_r_wheel_bumper - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - fr_caster_l_wheel_link_geom - 100.0 - - true - 100.0 - fr_caster_l_wheel_bumper - - - - - - - - - - - - 75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - fr_caster_r_wheel_link_geom - 100.0 - - true - 100.0 - fr_caster_r_wheel_bumper - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - bl_caster_l_wheel_link_geom - 100.0 - - true - 100.0 - bl_caster_l_wheel_bumper - - - - - - - - - - - - 75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - bl_caster_r_wheel_link_geom - 100.0 - - true - 100.0 - bl_caster_r_wheel_bumper - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - br_caster_l_wheel_link_geom - 100.0 - - true - 100.0 - br_caster_l_wheel_bumper - - - - - - - - - - - - 75.0676691729 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - br_caster_r_wheel_link_geom - 100.0 - - true - 100.0 - br_caster_r_wheel_bumper - - - - - - - - - - - - -75.0676691729 - - - - base_link_geom - 100.0 - - true - 100.0 - base_bumper - - - - - - - - - - base_link - - true - 100.0 - base_link - base_pose_ground_truth - 0.01 - map - 25.7 25.7 0 - 0 0 0 - - - - true - 100.0 - plug_holder - plug_holder_pose_ground_truth - 0.01 - map - 0 0 0 - 0 0 0 - - - - - 640 - 640 - 1 - 0.0 0.0 0.0 - false - - -135 - 135 - - 0.05 - 10.0 - 0.01 - 20.0 - - 0.005 - true - 20.0 - base_scan - base_laser_link - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - torso_lift_link_geom - 100.0 - - true - 100.0 - torso_lift_bumper - - - - - - - true - 100.0 - torso_lift_link - imu_data - 0.01 - map - 0 0 0 - 0 0 0 - - - - - - -52143.33 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 6.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 6.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - R8G8B8 - 2448 2050 - 45 - 0.1 - 100 - 20.0 - - true - 20.0 - prosilica/cam_info - prosilica/image - prosilica/image_rect - prosilica/cam_info_service - prosilica/poll - hight_def_optical_frame - 1224.5 - 1224.5 - 1025.5 - 2955 - 0 - 0 - 0 - 0 - 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 20.0 - - true - 20.0 - wide_stereo/left_image - wide_stereo_l_stereo_camera_frame - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 20.0 - - true - 20.0 - wide_stereo/right_image - wide_stereo_r_stereo_camera_frame - - - - - - - true - 20.0 - wide_stereo_l_sensor - wide_stereo_r_sensor - wide_stereo/raw_stereo - wide_stereo_optical_frame - 320 - 320 - 240 - 320 - 0 - 0 - 0 - 0 - 0 - -0.09 - - - - - - - - - 640 480 - L8 - 45 - 0.1 - 100 - 20.0 - - true - 20.0 - narrow_stereo/left_image - narrow_stereo_l_stereo_camera_frame - - - - - - - 640 480 - L8 - 45 - 0.1 - 100 - 20.0 - - true - 20.0 - narrow_stereo/right_image - narrow_stereo_r_stereo_camera_frame - - - - - - - true - 20.0 - narrow_stereo_l_sensor - narrow_stereo_r_sensor - narrow_stereo/raw_stereo - narrow_stereo_optical_frame - 320 - 320 - 240 - 772.55 - 0 - 0 - 0 - 0 - 0 - -0.09 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 - 640 - 1 - - 0.0 0.0 0.0 - false - - -80 - 80 - - 0.05 - 10.0 - 0.01 - 40.0 - - 0.005 - true - 40.0 - tilt_scan - laser_tilt_link - - - - - - - 6.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - r_shoulder_pan_link_geom - 100.0 - - true - 100.0 - r_shoulder_pan_bumper - - - - - true - - - - - - r_shoulder_lift_link_geom - 100.0 - - true - 100.0 - r_r_shoulder_lift_bumper - - - - true - - - - - - true - - - - - - - r_upper_arm_link_geom - 100.0 - - true - 100.0 - r_upper_arm_bumper - - - - true - - - - r_elbow_flex_link_geom - 100.0 - - true - 100.0 - r_elbow_flex_bumper - - - - - true - - - - - - true - - - - true - - r_forearm_link_geom - 100.0 - - true - 100.0 - r_forearm_bumper - - - - - - true - - r_wrist_flex_link_geom - 100.0 - - true - 100.0 - r_wrist_flex_bumper - - - - - - - - - true - - r_wrist_roll_link_geom - 100.0 - - true - 100.0 - r_wrist_roll_bumper - - - - - - - - - - 63.16 - - - - 61.89 - - - - 32.65 - - - - -36.17 - - - - 90.5142857143 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - r_gripper_l_finger_link_geom - 100.0 - - true - 100.0 - r_gripper_l_finger_bumper - - - - - - - - - - - - - - - - true - - r_gripper_r_finger_link_geom - 100.0 - - true - 100.0 - r_gripper_r_finger_bumper - - - - - - - - - - - - - - - true - - - r_gripper_l_finger_tip_link_geom - 100.0 - - true - 100.0 - r_gripper_l_finger_tip_bumper - - - - - - - - - - - - - - - true - - - r_gripper_r_finger_tip_link_geom - 100.0 - - true - 100.0 - r_gripper_r_finger_tip_bumper - - - - - - - - - - - true - 100.0 - r_gripper_l_finger_link - r_gripper_l_finger_pose_ground_truth - 0.0 - map - - - - true - 100.0 - r_gripper_l_finger_link - r_gripper_l_finger_force_ground_truth - r_gripper_l_finger_link - - - - - - - - - - - - - true - - r_gripper_palm_link_geom - 100.0 - - true - 100.0 - r_gripper_palm_bumper - - - - - - true - - - - r_gripper_l_finger_tip_link - r_gripper_float_link - r_gripper_l_finger_tip_link - 0 1 0 - 0 0 0 - - - r_gripper_r_finger_tip_link - r_gripper_float_link - r_gripper_r_finger_tip_link - 0 1 0 - 0 0 0 - - - - - true - 100.0 - r_gripper_palm_link - r_gripper_palm_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - map - - - - true - 100.0 - r_gripper_tool_frame - r_gripper_tool_frame_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - /map - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - l_shoulder_pan_link_geom - 100.0 - - true - 100.0 - l_shoulder_pan_bumper - - - - - true - - - - - - l_shoulder_lift_link_geom - 100.0 - - true - 100.0 - l_r_shoulder_lift_bumper - - - - true - - - - - - true - - - - - - - l_upper_arm_link_geom - 100.0 - - true - 100.0 - l_upper_arm_bumper - - - - true - - - - l_elbow_flex_link_geom - 100.0 - - true - 100.0 - l_elbow_flex_bumper - - - - - true - - - - - - true - - - - true - - l_forearm_link_geom - 100.0 - - true - 100.0 - l_forearm_bumper - - - - - - true - - l_wrist_flex_link_geom - 100.0 - - true - 100.0 - l_wrist_flex_bumper - - - - - - - - - true - - l_wrist_roll_link_geom - 100.0 - - true - 100.0 - l_wrist_roll_bumper - - - - - - - - - - 63.16 - - - - 61.89 - - - - 32.65 - - - - -36.17 - - - - 90.5142857143 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - l_gripper_l_finger_link_geom - 100.0 - - true - 100.0 - l_gripper_l_finger_bumper - - - - - - - - - - - - - - - - true - - l_gripper_r_finger_link_geom - 100.0 - - true - 100.0 - l_gripper_r_finger_bumper - - - - - - - - - - - - - - - true - - - l_gripper_l_finger_tip_link_geom - 100.0 - - true - 100.0 - l_gripper_l_finger_tip_bumper - - - - - - - - - - - - - - - true - - - l_gripper_r_finger_tip_link_geom - 100.0 - - true - 100.0 - l_gripper_r_finger_tip_bumper - - - - - - - - - - - true - 100.0 - l_gripper_l_finger_link - l_gripper_l_finger_pose_ground_truth - 0.0 - map - - - - true - 100.0 - l_gripper_l_finger_link - l_gripper_l_finger_force_ground_truth - l_gripper_l_finger_link - - - - - - - - - - - - - true - - l_gripper_palm_link_geom - 100.0 - - true - 100.0 - l_gripper_palm_bumper - - - - - - true - - - - l_gripper_l_finger_tip_link - l_gripper_float_link - l_gripper_l_finger_tip_link - 0 1 0 - 0 0 0 - - - l_gripper_r_finger_tip_link - l_gripper_float_link - l_gripper_r_finger_tip_link - 0 1 0 - 0 0 0 - - - - - true - 100.0 - l_gripper_palm_link - l_gripper_palm_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - map - - - - true - 100.0 - l_gripper_tool_frame - l_gripper_tool_frame_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - /map - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 20.0 - - true - 20.0 - l_forearm_cam/image - l_forearm_cam_frame - - - - true - PR2/Blue - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 20.0 - - true - 20.0 - r_forearm_cam/image - r_forearm_cam_frame - - - - true - PR2/Blue - - true - - - - - - - diff --git a/urdf/test/fail_pr2_desc_no_joint2.urdf b/urdf/test/fail_pr2_desc_no_joint2.urdf deleted file mode 100644 index be1fdbc9..00000000 --- a/urdf/test/fail_pr2_desc_no_joint2.urdf +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_parent_itself.urdf b/urdf/test/fail_pr2_desc_parent_itself.urdf deleted file mode 100644 index 5eda24d4..00000000 --- a/urdf/test/fail_pr2_desc_parent_itself.urdf +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_pr2_desc_two_trees.urdf b/urdf/test/fail_pr2_desc_two_trees.urdf deleted file mode 100644 index 415e74c1..00000000 --- a/urdf/test/fail_pr2_desc_two_trees.urdf +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/fail_three_links_one_joint.urdf b/urdf/test/fail_three_links_one_joint.urdf deleted file mode 100644 index a6766a9d..00000000 --- a/urdf/test/fail_three_links_one_joint.urdf +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/no_visual.urdf b/urdf/test/no_visual.urdf deleted file mode 100644 index 0554bac5..00000000 --- a/urdf/test/no_visual.urdf +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/urdf/test/one_link.urdf b/urdf/test/one_link.urdf deleted file mode 100644 index 4d99c963..00000000 --- a/urdf/test/one_link.urdf +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/pr2_desc.urdf b/urdf/test/pr2_desc.urdf deleted file mode 100644 index cbc5c776..00000000 --- a/urdf/test/pr2_desc.urdf +++ /dev/null @@ -1,3238 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - true - 1000.0 - - - - true - 1.0 - 5 - - power_state - 10.0 - 87.78 - -474 - 525 - 15.52 - 16.41 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 - 640 - 1 - 0.0 0.0 0.0 - false - -129.998394137 - 129.998394137 - 0.08 - 10.0 - 0.01 - 20 - - 0.005 - true - 20 - base_scan - base_laser_link - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 79.2380952381 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -79.2380952381 - - - - - - true - - base_link_geom - 100.0 - - true - 100.0 - base_bumper - - - - - - - true - 100.0 - base_link - base_pose_ground_truth - 0.01 - map - 25.7 25.7 0 - - 0 0 0 - - - base_footprint - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - torso_lift_link_geom - 100.0 - - true - 100.0 - torso_lift_bumper - - - - - - - - -52143.33 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - 100.0 - imu_link - torso_lift_imu/data - 2.89e-08 - 0 0 0 - 0 0 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 6.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 6.0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - R8G8B8 - 2448 2050 - 45 - 0.1 - 100 - 20.0 - - true - 20.0 - /prosilica/image_raw - /prosilica/camera_info - /prosilica/request_image - high_def_frame - 1224.5 - 1224.5 - 1025.5 - 2955 - - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - BAYER_BGGR8 - 90 - 0.1 - 100 - 25.0 - - true - 25.0 - wide_stereo/left/image_raw - wide_stereo/left/camera_info - wide_stereo_optical_frame - 0 - 320.5 - 320.5 - 240.5 - - - 320 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - BAYER_BGGR8 - 90 - 0.1 - 100 - 25.0 - - true - 25.0 - wide_stereo/right/image_raw - wide_stereo/right/camera_info - wide_stereo_optical_frame - 0.09 - 320.5 - 320.5 - 240.5 - - - 320 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 45 - 0.1 - 100 - 25.0 - - true - 25.0 - narrow_stereo/left/image_raw - narrow_stereo/left/camera_info - narrow_stereo_optical_frame - 0 - 320.5 - 320.5 - 240.5 - - - 772.55 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 45 - 0.1 - 100 - 25.0 - - true - 25.0 - narrow_stereo/right/image_raw - narrow_stereo/right/camera_info - narrow_stereo_optical_frame - 0.09 - 320.5 - 320.5 - 240.5 - - - 772.55 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - 15.0 - stereo_projection_pattern_high_res_red.png - projector_wg6802418_child_frame - stereo_projection_pattern_filter.png - projector_wg6802418_controller/image - projector_wg6802418_controller/projector - 0.785398163397 - 0.4 - 10 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 - 640 - 1 - 0.0 0.0 0.0 - false - -79.9999999086 - 79.9999999086 - 0.08 - 10.0 - 0.01 - 40 - - 0.005 - true - 40 - tilt_scan - laser_tilt_link - - - - - - - - - - -6.05 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - - - 32.6525111499 - - - true - - - - - - - true - - - - - - - - - 63.1552452977 - - - - - 61.8948225713 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - -90.5142857143 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -1.0 - - - true - - - - - - - - - -36.167452007 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - true - - - - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - r_gripper_l_finger_link_geom - 100.0 - - true - 100.0 - r_gripper_l_finger_link - r_gripper_l_finger_bumper - - - - - - - - - - - - - - - - - true - - r_gripper_r_finger_link_geom - 100.0 - - true - r_gripper_r_finger_link - 100.0 - r_gripper_r_finger_bumper - - - - - - - - - - - - - - - - true - false - - r_gripper_l_finger_tip_link_geom - 100.0 - - true - r_gripper_l_finger_tip_link - 100.0 - r_gripper_l_finger_tip_bumper - - - - - - - - - - - - - - - - true - false - - r_gripper_r_finger_tip_link_geom - 100.0 - - true - r_gripper_r_finger_tip_link - 100.0 - r_gripper_r_finger_tip_bumper - - - - - - - - - - - true - 100.0 - r_gripper_l_finger_link - r_gripper_l_finger_pose_ground_truth - 0.0 - base_link - - - - true - 100.0 - r_gripper_l_finger_link - r_gripper_l_finger_force_ground_truth - r_gripper_l_finger_link - - - - - - - - - - - - true - 0.17126 - 7.7562e-05 - 1.49095e-06 - -9.83385e-06 - 0.000197083 - -3.06125e-06 - 0.000181054 - 0.03598 - 0.0173 - -0.00164 - 0.82991 -0.157 0.790675 - 0 -0 0 - true - false - - - true - 0.17389 - 7.73841e-05 - -2.09309e-06 - -8.36228e-06 - 0.000198474 - 2.4611e-06 - 0.00018107 - 0.03576 - -0.01736 - -0.00095 - 0.82991 -0.219 0.790675 - 0 -0 0 - true - false - - - - - r_gripper_r_parallel_link - r_gripper_palm_link - r_gripper_palm_link - 0 0 -1 - 0.2 - 0.05891 -0.031 0 - - - r_gripper_l_parallel_link - r_gripper_palm_link - r_gripper_palm_link - 0 0 1 - 0.2 - 0.05891 0.031 0 - - - r_gripper_r_parallel_link - r_gripper_r_finger_tip_link - r_gripper_r_finger_tip_link - 0 0 1 - -0.018 -0.021 0 - - - r_gripper_l_parallel_link - r_gripper_l_finger_tip_link - r_gripper_l_finger_tip_link - 0 0 1 - -0.018 0.021 0 - - - r_gripper_l_finger_tip_link - r_gripper_r_finger_tip_link - r_gripper_r_finger_tip_link - 0 1 0 - - - - true - - - - true - - - - - - - - - - - - - true - - r_gripper_palm_link_geom - 100.0 - - true - 100.0 - r_gripper_palm_link - r_gripper_palm_bumper - - - - - - - true - 100.0 - r_gripper_palm_link - r_gripper_palm_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - map - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - - - 32.6525111499 - - - true - - - - - - - true - - - - - - - - - 63.1552452977 - - - - - 61.8948225713 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - - - - -90.5142857143 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -1.0 - - - true - - - - - - - - - -36.167452007 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - true - - - - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - l_gripper_l_finger_link_geom - 100.0 - - true - 100.0 - l_gripper_l_finger_link - l_gripper_l_finger_bumper - - - - - - - - - - - - - - - - - true - - l_gripper_r_finger_link_geom - 100.0 - - true - l_gripper_r_finger_link - 100.0 - l_gripper_r_finger_bumper - - - - - - - - - - - - - - - - true - false - - l_gripper_l_finger_tip_link_geom - 100.0 - - true - l_gripper_l_finger_tip_link - 100.0 - l_gripper_l_finger_tip_bumper - - - - - - - - - - - - - - - - true - false - - l_gripper_r_finger_tip_link_geom - 100.0 - - true - l_gripper_r_finger_tip_link - 100.0 - l_gripper_r_finger_tip_bumper - - - - - - - - - - - true - 100.0 - l_gripper_l_finger_link - l_gripper_l_finger_pose_ground_truth - 0.0 - base_link - - - - true - 100.0 - l_gripper_l_finger_link - l_gripper_l_finger_force_ground_truth - l_gripper_l_finger_link - - - - - - - - - - - - true - 0.17126 - 7.7562e-05 - 1.49095e-06 - -9.83385e-06 - 0.000197083 - -3.06125e-06 - 0.000181054 - 0.03598 - 0.0173 - -0.00164 - 0.82991 0.219 0.790675 - 0 -0 0 - true - false - - - true - 0.17389 - 7.73841e-05 - -2.09309e-06 - -8.36228e-06 - 0.000198474 - 2.4611e-06 - 0.00018107 - 0.03576 - -0.01736 - -0.00095 - 0.82991 0.157 0.790675 - 0 -0 0 - true - false - - - - - l_gripper_r_parallel_link - l_gripper_palm_link - l_gripper_palm_link - 0 0 -1 - 0.2 - 0.05891 -0.031 0 - - - l_gripper_l_parallel_link - l_gripper_palm_link - l_gripper_palm_link - 0 0 1 - 0.2 - 0.05891 0.031 0 - - - l_gripper_r_parallel_link - l_gripper_r_finger_tip_link - l_gripper_r_finger_tip_link - 0 0 1 - -0.018 -0.021 0 - - - l_gripper_l_parallel_link - l_gripper_l_finger_tip_link - l_gripper_l_finger_tip_link - 0 0 1 - -0.018 0.021 0 - - - l_gripper_l_finger_tip_link - l_gripper_r_finger_tip_link - l_gripper_r_finger_tip_link - 0 1 0 - - - - true - - - - true - - - - - - - - - - - - - true - - l_gripper_palm_link_geom - 100.0 - - true - 100.0 - l_gripper_palm_link - l_gripper_palm_bumper - - - - - - - true - 100.0 - l_gripper_palm_link - l_gripper_palm_pose_ground_truth - 0 0 0 - 0 0 0 - 0.0 - map - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 25.0 - - true - 25.0 - l_forearm_cam/image_raw - l_forearm_cam/camera_info - l_forearm_cam_optical_frame - 0 - 320.5 - 320.5 - 240.5 - - - 320 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 640 480 - L8 - 90 - 0.1 - 100 - 25.0 - - true - 25.0 - r_forearm_cam/image_raw - r_forearm_cam/camera_info - r_forearm_cam_optical_frame - 0 - 320.5 - 320.5 - 240.5 - - - 320 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - 0.00000001 - - - - true - PR2/Blue - - diff --git a/urdf/test/pr2_desc_no_joint.urdf b/urdf/test/pr2_desc_no_joint.urdf deleted file mode 100644 index 11fc4fd9..00000000 --- a/urdf/test/pr2_desc_no_joint.urdf +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/urdf/test/singularity.urdf b/urdf/test/singularity.urdf deleted file mode 100644 index ed91f44d..00000000 --- a/urdf/test/singularity.urdf +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/test_robot.urdf b/urdf/test/test_robot.urdf deleted file mode 100644 index 731e1f30..00000000 --- a/urdf/test/test_robot.urdf +++ /dev/null @@ -1,425 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp deleted file mode 100644 index a730eb51..00000000 --- a/urdf/test/test_robot_model_parser.cpp +++ /dev/null @@ -1,172 +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. -*********************************************************************/ - -/* Author: Wim Meeussen */ - -#include -#include -#include "urdf/model.h" - -// Including ros, just to be able to call ros::init(), to remove unwanted -// args from command-line. -#include - -using namespace urdf; - -int g_argc; -char** g_argv; - -class TestParser : public testing::Test -{ -public: - - bool checkModel(urdf::Model & robot) - { - // get root link - urdf::LinkConstSharedPtr root_link = robot.getRoot(); - if (!root_link) - { - ROS_ERROR("no root link %s", robot.getName().c_str()); - return false; - } - - // go through entire tree - return this->traverse_tree(root_link); - - }; - -protected: - /// constructor - // num_links starts at 1 because traverse_tree doesn't count the root node - TestParser() : num_joints(0), num_links(1) - { - } - - - /// Destructor - ~TestParser() - { - } - - bool traverse_tree(urdf::LinkConstSharedPtr link,int level = 0) - { - ROS_INFO("Traversing tree at level %d, link size %lu", level, link->child_links.size()); - level+=2; - bool retval = true; - for (std::vector::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) - { - ++num_links; - if (*child && (*child)->parent_joint) - { - ++num_joints; - // check rpy - double roll,pitch,yaw; - (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(roll,pitch,yaw); - - if (std::isnan(roll) || std::isnan(pitch) || std::isnan(yaw)) - { - ROS_ERROR("getRPY() returned nan!"); - return false; - } - // recurse down the tree - retval &= this->traverse_tree(*child,level); - } - else - { - ROS_ERROR("root link: %s has a null child!",link->name.c_str()); - return false; - } - } - // no more children - return retval; - }; - - size_t num_joints; - size_t num_links; -}; - - - - -TEST_F(TestParser, test) -{ - ASSERT_GE(g_argc, 3); - std::string folder = std::string(g_argv[1]) + "/test/"; - ROS_INFO("Folder %s",folder.c_str()); - std::string file = std::string(g_argv[2]); - bool expect_success = (file.substr(0,5) != "fail_"); - urdf::Model robot; - ROS_INFO("Parsing file %s, expecting %d",(folder + file).c_str(), expect_success); - if (!expect_success) { - ASSERT_FALSE(robot.initFile(folder + file)); - return; - } - - ASSERT_EQ(g_argc, 7); - std::string robot_name = std::string(g_argv[3]); - std::string root_name = std::string(g_argv[4]); - size_t expected_num_joints = atoi(g_argv[5]); - size_t expected_num_links = atoi(g_argv[6]); - - ASSERT_TRUE(robot.initFile(folder + file)); - - EXPECT_EQ(robot.getName(), robot_name); - urdf::LinkConstSharedPtr root = robot.getRoot(); - ASSERT_TRUE(static_cast(root)); - EXPECT_EQ(root->name, root_name); - - ASSERT_TRUE(checkModel(robot)); - EXPECT_EQ(num_joints, expected_num_joints); - EXPECT_EQ(num_links, expected_num_links); - EXPECT_EQ(robot.joints_.size(), expected_num_joints); - EXPECT_EQ(robot.links_.size(), expected_num_links); - - // test reading from parameter server - ASSERT_TRUE(robot.initParam("robot_description")); - ASSERT_FALSE(robot.initParam("robot_description_wim")); - SUCCEED(); -} - - - - -int main(int argc, char** argv) -{ - // Calling ros::init(), just to remove unwanted args from command-line. - ros::init(argc, argv, "test", ros::init_options::AnonymousName); - testing::InitGoogleTest(&argc, argv); - g_argc = argc; - g_argv = argv; - return RUN_ALL_TESTS(); -} diff --git a/urdf/test/test_robot_model_parser.launch b/urdf/test/test_robot_model_parser.launch deleted file mode 100644 index 9953b55a..00000000 --- a/urdf/test/test_robot_model_parser.launch +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/two_links_one_joint.urdf b/urdf/test/two_links_one_joint.urdf deleted file mode 100644 index a4cf276f..00000000 --- a/urdf/test/two_links_one_joint.urdf +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/urdf/test/urdfdom_compatibility.cpp b/urdf/test/urdfdom_compatibility.cpp deleted file mode 100644 index 13524811..00000000 --- a/urdf/test/urdfdom_compatibility.cpp +++ /dev/null @@ -1,53 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2017 Open Source Robotics Foundation -* 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 -#include "urdf/model.h" - - -TEST(UrdfCompatibility, UpcastSharedPtr) -{ - urdf::ModelSharedPtr model(new urdf::Model); - model->name_ = "UpcastSharedPtr"; - urdf::ModelInterfaceSharedPtr interface = model; - EXPECT_EQ(std::string("UpcastSharedPtr"), interface->getName()); -} - - -int main(int argc, char** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - diff --git a/urdf/urdfdom_compatibility.h.in b/urdf/urdfdom_compatibility.h.in deleted file mode 100644 index 7ee6cba2..00000000 --- a/urdf/urdfdom_compatibility.h.in +++ /dev/null @@ -1,107 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2016, CITEC, Bielefeld University -* 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. -*********************************************************************/ - -/* Robert Haschke */ - -#ifndef URDF_URDFDOM_COMPATIBILITY_ -#define URDF_URDFDOM_COMPATIBILITY_ - -#define URDFDOM_HEADERS_MAJOR_VERSION @URDFDOM_HEADERS_MAJOR_VERSION@ -#define URDFDOM_HEADERS_MINOR_VERSION @URDFDOM_HEADERS_MINOR_VERSION@ -#define URDFDOM_HEADERS_REVISION_VERSION @URDFDOM_HEADERS_REVISION_VERSION@ - -// Define shared pointers for urdfdom versions less than 0.4 -// Plus define ModelSharedPtr for 0.4 -#if URDFDOM_HEADERS_MAJOR_VERSION == 0 && URDFDOM_HEADERS_MINOR_VERSION <= 4 - -#include -#include - -#define URDF_TYPEDEF_CLASS_POINTER(Class) \ -class Class; \ -typedef boost::shared_ptr Class##SharedPtr; \ -typedef boost::shared_ptr Class##ConstSharedPtr; \ -typedef boost::weak_ptr Class##WeakPtr - -namespace urdf { -// These shared_ptrs were added to urdfdom in 0.4.0, -// so if urdfdom == 0.4 this is duplicate work -URDF_TYPEDEF_CLASS_POINTER(Box); -URDF_TYPEDEF_CLASS_POINTER(Collision); -URDF_TYPEDEF_CLASS_POINTER(Cylinder); -URDF_TYPEDEF_CLASS_POINTER(Geometry); -URDF_TYPEDEF_CLASS_POINTER(Inertial); - -URDF_TYPEDEF_CLASS_POINTER(Joint); -URDF_TYPEDEF_CLASS_POINTER(JointCalibration); -URDF_TYPEDEF_CLASS_POINTER(JointDynamics); -URDF_TYPEDEF_CLASS_POINTER(JointLimits); -URDF_TYPEDEF_CLASS_POINTER(JointMimic); -URDF_TYPEDEF_CLASS_POINTER(JointSafety); - -URDF_TYPEDEF_CLASS_POINTER(Link); -URDF_TYPEDEF_CLASS_POINTER(Material); -URDF_TYPEDEF_CLASS_POINTER(Mesh); -URDF_TYPEDEF_CLASS_POINTER(Sphere); -URDF_TYPEDEF_CLASS_POINTER(Visual); - -URDF_TYPEDEF_CLASS_POINTER(ModelInterface); - -// ModelSharedPtr is the only one that needs to be defined for urdfdom 0.4 -URDF_TYPEDEF_CLASS_POINTER(Model); -} - -#undef URDF_TYPEDEF_CLASS_POINTER - -#else // urdfdom <= 0.4 - -#include -#include - -namespace urdf { -typedef std::shared_ptr ModelInterfaceSharedPtr; -typedef std::shared_ptr ModelInterfaceConstSharedPtr; -typedef std::weak_ptr ModelInterfaceWeakPtr; - -// Forward declaration -class Model; - -typedef std::shared_ptr ModelSharedPtr; -typedef std::shared_ptr ModelConstSharedPtr; -typedef std::weak_ptr ModelWeakPtr; -} - -#endif // urdfdom > 0.4 - -#endif // URDF_URDFDOM_COMPATIBILITY_ diff --git a/urdf_parser_plugin/CHANGELOG.rst b/urdf_parser_plugin/CHANGELOG.rst deleted file mode 100644 index a349fe82..00000000 --- a/urdf_parser_plugin/CHANGELOG.rst +++ /dev/null @@ -1,82 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package urdf_parser_plugin -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.12.11 (2017-06-27) --------------------- - -1.12.10 (2017-06-24) --------------------- - -1.12.9 (2017-04-26) -------------------- - -1.12.8 (2017-03-27) -------------------- -* add Chris and Shane as maintainers (`#184 `_) -* Contributors: William Woodall - -1.12.7 (2017-01-26) -------------------- - -1.12.6 (2017-01-04) -------------------- -* Now using ``urdf::*ShredPtr`` instead of ``boost::shared_ptr`` (`#144 `_) -* Contributors: Jochen Sprickerhof - -1.12.5 (2016-10-27) -------------------- - -1.12.4 (2016-08-23) -------------------- - -1.12.3 (2016-06-10) -------------------- - -1.12.2 (2016-04-12) -------------------- - -1.12.1 (2016-04-10) -------------------- - -1.11.8 (2015-09-11) -------------------- - -1.11.7 (2015-04-22) -------------------- - -1.11.6 (2014-11-30) -------------------- - -1.11.5 (2014-07-24) -------------------- - -1.11.4 (2014-07-07) -------------------- -* moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 -* Contributors: Tully Foote - -1.11.3 (2014-06-24) -------------------- -* update usage of urdfdom_headers for indigo/trusty -* Contributors: William Woodall - -1.11.2 (2014-03-22) -------------------- - -1.11.1 (2014-03-20) -------------------- - -1.11.0 (2014-02-21) -------------------- - -1.10.18 (2013-12-04) --------------------- -* add DEPENDS for kdl_parser -* Contributors: Ioan Sucan - -1.10.16 (2013-11-18) --------------------- - -1.10.15 (2013-08-17) --------------------- diff --git a/urdf_parser_plugin/CMakeLists.txt b/urdf_parser_plugin/CMakeLists.txt deleted file mode 100644 index 75c68547..00000000 --- a/urdf_parser_plugin/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(urdf_parser_plugin) - -find_package(catkin REQUIRED) -find_package(urdfdom_headers REQUIRED) - -catkin_package( - INCLUDE_DIRS include - DEPENDS urdfdom_headers -) - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) diff --git a/urdf_parser_plugin/include/urdf_parser_plugin/parser.h b/urdf_parser_plugin/include/urdf_parser_plugin/parser.h deleted file mode 100644 index 92de4113..00000000 --- a/urdf_parser_plugin/include/urdf_parser_plugin/parser.h +++ /dev/null @@ -1,62 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2013, 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 */ - -#ifndef URDF_PARSER_PLUGIN_H -#define URDF_PARSER_PLUGIN_H - -#include - -namespace urdf -{ - -/** \brief Base class for URDF parsers */ -class URDFParser -{ -public: - URDFParser() - { - } - virtual ~URDFParser() - { - } - - /// \brief Load Model from string - virtual urdf::ModelInterfaceSharedPtr parse(const std::string &xml_string) = 0; -}; - -} - -#endif diff --git a/urdf_parser_plugin/package.xml b/urdf_parser_plugin/package.xml deleted file mode 100644 index 9615cb8a..00000000 --- a/urdf_parser_plugin/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - urdf_parser_plugin - 1.12.11 - - This package contains a C++ base class for URDF parsers. - - - Ioan Sucan - Jackie Kay - Chris Lalancette - Shane Loretz - - BSD - - http://ros.org/wiki/urdf - https://github.com/ros/robot_model - https://github.com/ros/robot_model/issues - - catkin - liburdfdom-headers-dev - liburdfdom-headers-dev - -