remove deprecated packages, rename visualization/ to joint_state_publisher/, catkinize joint_state_publisher
This commit is contained in:
parent
854eb1fe57
commit
bb8cc5ac14
|
@ -0,0 +1,8 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(joint_state_publisher)
|
||||
|
||||
find_package(catkin)
|
||||
|
||||
catkin_python_setup()
|
||||
|
||||
catkin_package()
|
|
@ -0,0 +1,22 @@
|
|||
<package>
|
||||
<name>joint_state_publisher</name>
|
||||
<version>1.9.32</version>
|
||||
<description>
|
||||
This package contains a tool for setting and publishing joint state values for a given URDF.
|
||||
</description>
|
||||
<author email="davidlu@wustl.edu">David Lu!!!</author>
|
||||
<maintainer email="davidlu@wustl.edu">David Lu!!!</maintainer>
|
||||
<license>BSD</license>
|
||||
<url type="website">http://www.ros.org/wiki/joint_state_publisher</url>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>rospy</build_depend>
|
||||
<build_depend>wxpython</build_depend>
|
||||
<build_depend>sensor_msgs</build_depend>
|
||||
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>wxpython</run_depend>
|
||||
<run_depend>sensor_msgs</run_depend>
|
||||
|
||||
</package>
|
Before Width: | Height: | Size: 11 KiB After Width: | Height: | Size: 11 KiB |
|
@ -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)
|
|
@ -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)
|
|
@ -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 <srdfdom/model.h>"
|
||||
|
||||
#include <srdfdom/model.h>
|
||||
|
||||
#endif
|
|
@ -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.
|
||||
|
||||
<!--
|
||||
Provide an overview of your package.
|
||||
-->
|
||||
|
||||
|
||||
*/
|
|
@ -1,24 +0,0 @@
|
|||
<package>
|
||||
<name>srdf</name>
|
||||
<version>1.9.32</version>
|
||||
|
||||
<description>
|
||||
|
||||
SRDF (Semantic Robot Description Format) is a representation of
|
||||
semantic information about robots.
|
||||
|
||||
</description>
|
||||
<author>Ioan Sucan</author>
|
||||
<maintainer email="isucan@willowgarage.com">Ioan Sucan</maintainer> <license>BSD</license>
|
||||
|
||||
<url type="website">http://ros.org/wiki/srdf</url>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>srdfdom</build_depend>
|
||||
<build_depend>tinyxml</build_depend>
|
||||
|
||||
<run_depend>srdfdom</run_depend>
|
||||
<run_depend>tinyxml</run_depend>
|
||||
|
||||
</package>
|
|
@ -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)
|
|
@ -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 <urdf_model/color.h>"
|
||||
|
||||
#include <urdf_model/color.h>
|
||||
|
||||
#endif
|
|
@ -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 <urdf_model/joint.h>"
|
||||
|
||||
#include <urdf_model/joint.h>
|
||||
|
||||
#endif
|
|
@ -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 <urdf_model/link.h>"
|
||||
|
||||
#include <urdf_model/link.h>
|
||||
|
||||
#endif
|
|
@ -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 <urdf_model/model.h>"
|
||||
|
||||
#include <urdf_model/model.h>
|
||||
|
||||
#endif
|
|
@ -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 <urdf_model/pose.h>"
|
||||
|
||||
#include <urdf_model/pose.h>
|
||||
|
||||
#endif
|
|
@ -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
|
||||
<joint name="J" type="revolute">
|
||||
<dynamics damping="1" friction="0"/>
|
||||
<limit lower="0.9" upper="2.1" effort="1000" velocity="1"/>
|
||||
<safety_controller soft_lower_limit="0.7" soft_upper_limit="2.1" k_position="1" k_velocity="1" />
|
||||
<calibration reference_position="0.7" />
|
||||
<mimic joint="J100" offset="0" multiplier="0.7" />
|
||||
|
||||
<!-- origin: origin of the joint in the parent frame -->
|
||||
<!-- child link frame is the joint frame -->
|
||||
<!-- axis is in the joint frame -->
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="P"/>
|
||||
<child link="C"/>
|
||||
</joint>
|
||||
|
||||
<link name="C">
|
||||
<inertial>
|
||||
<mass value="10"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="Green"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="1.01 1.01 1.01"/>
|
||||
</geometry>
|
||||
<contact_coefficient mu="0" resitution="0" k_p="0" k_d="0" />
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<material name="Green">
|
||||
<texture filename="...texture file..." />
|
||||
<!--color rgb="255 255 255" /-->
|
||||
</material>
|
||||
@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
|
||||
|
||||
<!--
|
||||
\section rosapi ROS API
|
||||
|
||||
Names are very important in ROS because they can be remapped on the
|
||||
command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
|
||||
APPEAR IN THE CODE. You should list names of every topic, service and
|
||||
parameter used in your code. There is a template below that you can
|
||||
use to document each node separately.
|
||||
|
||||
List of nodes:
|
||||
- \b node_name1
|
||||
- \b node_name2
|
||||
-->
|
||||
|
||||
<!-- START: copy from here to 'END' for each node
|
||||
|
||||
<hr>
|
||||
|
||||
\subsection node_name node_name
|
||||
|
||||
node_name does (provide a basic description of your node)
|
||||
|
||||
\subsubsection Usage
|
||||
\verbatim
|
||||
$ node_type1 [standard ROS args]
|
||||
\endverbatim
|
||||
|
||||
\par Example
|
||||
|
||||
\verbatim
|
||||
$ node_type1
|
||||
\endverbatim
|
||||
|
||||
|
||||
\subsubsection topics ROS topics
|
||||
|
||||
Subscribes to:
|
||||
- \b "in": [std_msgs/FooType] description of in
|
||||
|
||||
Publishes to:
|
||||
- \b "out": [std_msgs/FooType] description of out
|
||||
|
||||
|
||||
\subsubsection parameters ROS parameters
|
||||
|
||||
Reads the following parameters from the parameter server
|
||||
|
||||
- \b "~param_name" : \b [type] description of param_name
|
||||
- \b "~my_param" : \b [string] description of my_param
|
||||
|
||||
Sets the following parameters on the parameter server
|
||||
|
||||
- \b "~param_name" : \b [type] description of param_name
|
||||
|
||||
|
||||
\subsubsection services ROS services
|
||||
- \b "foo_service": [std_srvs/FooType] description of foo_service
|
||||
|
||||
|
||||
END: copy for each node -->
|
||||
|
||||
|
||||
<!-- START: Uncomment if you have any command-line tools
|
||||
|
||||
\section commandline Command-line tools
|
||||
|
||||
This section is a catch-all for any additional tools that your package
|
||||
provides or uses that may be of use to the reader. For example:
|
||||
|
||||
- tools/scripts (e.g. rospack, roscd)
|
||||
- roslaunch .launch files
|
||||
- xmlparam files
|
||||
|
||||
\subsection script_name script_name
|
||||
|
||||
Description of what this script/file does.
|
||||
|
||||
\subsubsection Usage
|
||||
\verbatim
|
||||
$ ./script_name [args]
|
||||
\endverbatim
|
||||
|
||||
\par Example
|
||||
|
||||
\verbatim
|
||||
$ ./script_name foo bar
|
||||
\endverbatim
|
||||
|
||||
END: Command-Line Tools Section -->
|
||||
|
||||
*/
|
|
@ -1,24 +0,0 @@
|
|||
<package>
|
||||
<name>urdf_interface</name>
|
||||
<version>1.9.32</version>
|
||||
<description>
|
||||
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.
|
||||
</description>
|
||||
<author>Wim Meeussen</author>
|
||||
<author>John Hsu</author>
|
||||
<maintainer email="isucan@willowgarage.com">Ioan Sucan</maintainer>
|
||||
<license>BSD</license>
|
||||
<url type="website">http://ros.org/wiki/urdf_interface</url>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>urdfdom</build_depend>
|
||||
|
||||
<run_depend>urdfdom</run_depend>
|
||||
|
||||
</package>
|
||||
|
||||
|
|
@ -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)
|
|
@ -1 +0,0 @@
|
|||
include $(shell rospack find mk)/cmake_stack.mk
|
|
@ -1,5 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.4.6)
|
||||
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
|
||||
|
||||
rosbuild_init()
|
||||
|
|
@ -1 +0,0 @@
|
|||
include $(shell rospack find mk)/cmake.mk
|
|
@ -1,15 +0,0 @@
|
|||
<package>
|
||||
<description brief="A node for publishing joint angles">
|
||||
A node for publishing joint angles, either through a gui, or with
|
||||
default values.
|
||||
</description>
|
||||
<author>David Lu!!</author>
|
||||
<license>BSD</license>
|
||||
<review status="unreviewed" notes=""/>
|
||||
<url>http://ros.org/wiki/joint_state_publisher</url>
|
||||
<depend package="rospy" />
|
||||
<depend package="sensor_msgs" />
|
||||
<rosdep name="wxpython" />
|
||||
</package>
|
||||
|
||||
|
|
@ -1,11 +0,0 @@
|
|||
<stack>
|
||||
<description brief="Tools for use with URDF Models">This package contains a number of tools for making, viewing and using URDF models.</description>
|
||||
<author>Maintained by David Lu!!</author>
|
||||
<license>BSD</license>
|
||||
<review status="unreviewed" notes=""/>
|
||||
<url>http://ros.org/wiki/robot_model_visualization</url>
|
||||
<depend stack="common_msgs" /> <!-- sensor_msgs -->
|
||||
<depend stack="ros" />
|
||||
<depend stack="ros_comm" /> <!-- rospy -->
|
||||
|
||||
</stack>
|
Loading…
Reference in New Issue