Initial commit.
authorWalter Fetter Lages <w.fetter@ieee.org>
Wed, 28 Nov 2018 13:25:20 +0000 (11:25 -0200)
committerWalter Fetter Lages <w.fetter@ieee.org>
Wed, 28 Nov 2018 13:25:20 +0000 (11:25 -0200)
74 files changed:
.gitignore [new file with mode: 0644]
CMakeLists.txt [new file with mode: 0644]
Makefile [new file with mode: 0644]
bhand_description/CMakeLists.txt [new file with mode: 0644]
bhand_description/Makefile [new file with mode: 0644]
bhand_description/launch/bhand.launch [new file with mode: 0644]
bhand_description/launch/bhand_sim.launch [new file with mode: 0644]
bhand_description/manifest.xml [new file with mode: 0644]
bhand_description/meshes/bh_base.stl [new file with mode: 0644]
bhand_description/meshes/bh_link1.stl [new file with mode: 0644]
bhand_description/meshes/bh_link2.stl [new file with mode: 0644]
bhand_description/meshes/bh_link3.stl [new file with mode: 0644]
bhand_description/xacro/bhand.urdf.xacro [new file with mode: 0644]
bhand_description/xacro/bhand0.urdf.xacro [new file with mode: 0644]
bhand_description/xacro/bhand_base.urdf.xacro [new file with mode: 0644]
bhand_description/xacro/bhand_finger.urdf.xacro [new file with mode: 0644]
plier_description/launch/display.launch [new file with mode: 0644]
plier_description/launch/gazebo.launch [new file with mode: 0644]
plier_description/launch/plier.launch [new file with mode: 0644]
plier_description/launch/plier_sim.launch [new file with mode: 0644]
plier_description/manifest.xml [new file with mode: 0644]
plier_description/meshes/base_link.stl [new file with mode: 0644]
plier_description/meshes/link1.stl [new file with mode: 0644]
plier_description/meshes/link2.stl [new file with mode: 0644]
plier_description/urdf/plier.urdf [new file with mode: 0644]
stack.xml [new file with mode: 0644]
wam_control_gazebo/CMakeLists.txt [new file with mode: 0644]
wam_control_gazebo/Makefile [new file with mode: 0644]
wam_control_gazebo/mainpage.dox [new file with mode: 0644]
wam_control_gazebo/manifest.xml [new file with mode: 0644]
wam_control_gazebo/robot_sim_plugins.xml [new file with mode: 0644]
wam_control_gazebo/src/robot_sim_wam.cpp [new file with mode: 0644]
wam_controllers/CMakeLists.txt [new file with mode: 0644]
wam_controllers/Makefile [new file with mode: 0644]
wam_controllers/README [new file with mode: 0644]
wam_controllers/config/computed_torque_control.yaml [new file with mode: 0644]
wam_controllers/doc/urdf2kdl.txt [new file with mode: 0644]
wam_controllers/include/wam_controllers/computed_torque_controller.h [new file with mode: 0644]
wam_controllers/launch/computed_torque.launch [new file with mode: 0644]
wam_controllers/launch/computed_torque_table.launch [new file with mode: 0644]
wam_controllers/mainpage.dox [new file with mode: 0644]
wam_controllers/manifest.xml [new file with mode: 0644]
wam_controllers/src/computed_torque_controller.cpp [new file with mode: 0644]
wam_controllers/wam_controllers_plugins.xml [new file with mode: 0644]
wam_description/CMakeLists.txt [new file with mode: 0644]
wam_description/Makefile [new file with mode: 0644]
wam_description/launch/wam.launch [new file with mode: 0644]
wam_description/launch/wam_bhand.launch [new file with mode: 0644]
wam_description/launch/wam_bhand_sim.launch [new file with mode: 0644]
wam_description/launch/wam_sim.launch [new file with mode: 0644]
wam_description/launch/wam_table.launch [new file with mode: 0644]
wam_description/launch/wam_table_sim.launch [new file with mode: 0644]
wam_description/manifest.xml [new file with mode: 0644]
wam_description/meshes/wam1.stl [new file with mode: 0644]
wam_description/meshes/wam2.stl [new file with mode: 0644]
wam_description/meshes/wam3.stl [new file with mode: 0644]
wam_description/meshes/wam4.stl [new file with mode: 0644]
wam_description/meshes/wam5.stl [new file with mode: 0644]
wam_description/meshes/wam6.stl [new file with mode: 0644]
wam_description/meshes/wam7.stl [new file with mode: 0644]
wam_description/meshes/wambase.stl [new file with mode: 0644]
wam_description/xacro/.wam_j1.urdf.xacro.swo [new file with mode: 0644]
wam_description/xacro/wam.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_base.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_bhand.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j1.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j2.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j3.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j4.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j5.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j6.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_j7.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_table.urdf.xacro [new file with mode: 0644]
wam_description/xacro/wam_tool_plate.urdf.xacro [new file with mode: 0644]

diff --git a/.gitignore b/.gitignore
new file mode 100644 (file)
index 0000000..c1edc29
--- /dev/null
@@ -0,0 +1,51 @@
+devel/
+logs/
+build/
+bin/
+lib/
+msg_gen/
+srv_gen/
+msg/*Action.msg
+msg/*ActionFeedback.msg
+msg/*ActionGoal.msg
+msg/*ActionResult.msg
+msg/*Feedback.msg
+msg/*Goal.msg
+msg/*Result.msg
+msg/_*.py
+build_isolated/
+devel_isolated/
+
+# Generated by dynamic reconfigure
+*.cfgc
+/cfg/cpp/
+/cfg/*.py
+
+# Ignore generated docs
+#*.dox
+*.wikidoc
+
+# eclipse stuff
+.project
+.cproject
+
+# qcreator stuff
+CMakeLists.txt.user
+
+srv/_*.py
+*.pcd
+*.pyc
+qtcreator-*
+*.user
+
+/planning/cfg
+/planning/docs
+/planning/src
+
+*~
+
+# Emacs
+.#*
+
+# Catkin custom files
+CATKIN_IGNORE
diff --git a/CMakeLists.txt b/CMakeLists.txt
new file mode 100644 (file)
index 0000000..28105dd
--- /dev/null
@@ -0,0 +1,17 @@
+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.0)
diff --git a/Makefile b/Makefile
new file mode 100644 (file)
index 0000000..a818cca
--- /dev/null
+++ b/Makefile
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake_stack.mk
\ No newline at end of file
diff --git a/bhand_description/CMakeLists.txt b/bhand_description/CMakeLists.txt
new file mode 100644 (file)
index 0000000..f8f1c9c
--- /dev/null
@@ -0,0 +1,30 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type.  Options are:
+#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
+#  Debug          : w/ debug symbols, w/o optimization
+#  Release        : w/o debug symbols, w/ optimization
+#  RelWithDebInfo : w/ debug symbols, w/ optimization
+#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rosbuild_init()
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#rosbuild_genmsg()
+#uncomment if you have defined services
+#rosbuild_gensrv()
+
+#common commands for building c++ executables and libraries
+#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rosbuild_add_boost_directories()
+#rosbuild_link_boost(${PROJECT_NAME} thread)
+#rosbuild_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
diff --git a/bhand_description/Makefile b/bhand_description/Makefile
new file mode 100644 (file)
index 0000000..b75b928
--- /dev/null
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
diff --git a/bhand_description/launch/bhand.launch b/bhand_description/launch/bhand.launch
new file mode 100644 (file)
index 0000000..1875c7c
--- /dev/null
@@ -0,0 +1,5 @@
+<?xml version="1.0"?>
+<launch>
+       <param name="robot_description" command="$(find xacro)/xacro.py '$(find bhand_description)/xacro/bhand.urdf.xacro'" />
+       <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model bhand -z 0.1" respawn="false" output="screen" />
+</launch>
diff --git a/bhand_description/launch/bhand_sim.launch b/bhand_description/launch/bhand_sim.launch
new file mode 100644 (file)
index 0000000..09797be
--- /dev/null
@@ -0,0 +1,9 @@
+<?xml version="1.0"?>
+<launch>
+
+       <!-- Start Gazebo -->
+       <include file="$(find gazebo_worlds)/launch/empty_world.launch"/>
+
+
+       <include file="$(find bhand_description)/launch/bhand.launch" />
+</launch>
diff --git a/bhand_description/manifest.xml b/bhand_description/manifest.xml
new file mode 100644 (file)
index 0000000..80a2f17
--- /dev/null
@@ -0,0 +1,14 @@
+<package>
+  <description brief="bhand_description">
+
+     bhand_description
+
+  </description>
+  <author>Walter Fetter Lages</author>
+  <license>GNU</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/bhand_description</url>
+
+</package>
+
+
diff --git a/bhand_description/meshes/bh_base.stl b/bhand_description/meshes/bh_base.stl
new file mode 100644 (file)
index 0000000..dce76f7
Binary files /dev/null and b/bhand_description/meshes/bh_base.stl differ
diff --git a/bhand_description/meshes/bh_link1.stl b/bhand_description/meshes/bh_link1.stl
new file mode 100644 (file)
index 0000000..bf35bd9
Binary files /dev/null and b/bhand_description/meshes/bh_link1.stl differ
diff --git a/bhand_description/meshes/bh_link2.stl b/bhand_description/meshes/bh_link2.stl
new file mode 100644 (file)
index 0000000..f74e529
Binary files /dev/null and b/bhand_description/meshes/bh_link2.stl differ
diff --git a/bhand_description/meshes/bh_link3.stl b/bhand_description/meshes/bh_link3.stl
new file mode 100644 (file)
index 0000000..d9361c6
Binary files /dev/null and b/bhand_description/meshes/bh_link3.stl differ
diff --git a/bhand_description/xacro/bhand.urdf.xacro b/bhand_description/xacro/bhand.urdf.xacro
new file mode 100644 (file)
index 0000000..b8fb615
--- /dev/null
@@ -0,0 +1,63 @@
+<?xml version="1.0"?>
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+       xmlns:xacro="http://ros.org/wiki/xacro"
+       name="bhand">
+
+  <property name="M_PI" value="3.1415926535897931" />
+  
+  <include filename="$(find bhand_description)/xacro/bhand_base.urdf.xacro" />
+  <include filename="$(find bhand_description)/xacro/bhand_finger.urdf.xacro" />
+
+  <xacro:bhand_base>
+  </xacro:bhand_base>
+
+  <xacro:bhand_finger parent="bhand_link_base" joint="11" type="revolute">
+               <origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="${M_PI}" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link_base" joint="21" type="revolute">
+               <origin xyz="0.0 -0.02475 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="1.5" lower="-${M_PI}" upper="0.0" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link_base" joint="31" type="fixed">
+               <origin xyz="0.0 0.0 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="0.0" lower="0.0" upper="0.0" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link11" joint="12" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link21" joint="22" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link31" joint="32" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link12" joint="13" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link22" joint="23" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link32" joint="33" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+
+</robot>
+
diff --git a/bhand_description/xacro/bhand0.urdf.xacro b/bhand_description/xacro/bhand0.urdf.xacro
new file mode 100644 (file)
index 0000000..79f781a
--- /dev/null
@@ -0,0 +1,72 @@
+<?xml version="1.0"?>
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+       xmlns:xacro="http://ros.org/wiki/xacro"
+       name="bhand">
+
+  <property name="M_PI" value="3.1415926535897931" />
+  
+  <include filename="$(find bhand_description)/xacro/bhand_base.urdf.xacro" />
+  <include filename="$(find bhand_description)/xacro/bhand_finger.urdf.xacro" />
+
+  <xacro:bhand_base>
+  </xacro:bhand_base>
+
+       <link name="world" />
+
+       <joint name="bhand_origin" type="fixed">
+               <parent link="world"/>
+               <child link="bhand_origin" />
+               <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
+       </joint>
+
+
+  <xacro:bhand_finger parent="bhand_link_base" joint="11" type="revolute">
+               <origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="${M_PI}" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link_base" joint="21" type="revolute">
+               <origin xyz="0.0 -0.02475 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="1.5" lower="-${M_PI}" upper="0.0" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link_base" joint="31" type="fixed">
+               <origin xyz="0.0 0.0 0.1325" rpy="0.0 0 0" /> 
+               <limit effort="30" velocity="0.0" lower="0.0" upper="0.0" />
+               <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link11" joint="12" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link21" joint="22" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link31" joint="32" type="revolute">
+               <origin xyz="0.050 0.0 0.0" rpy="${M_PI/2} 0.0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link2.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link12" joint="13" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link22" joint="23" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+  <xacro:bhand_finger parent="bhand_link32" joint="33" type="revolute">
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <limit effort="30" velocity="1.5" lower="0.698131701" upper="2.44346095" />
+               <mesh filename="package://bhand_description/meshes/bh_link3.stl" />
+  </xacro:bhand_finger>
+
+</robot>
+
diff --git a/bhand_description/xacro/bhand_base.urdf.xacro b/bhand_description/xacro/bhand_base.urdf.xacro
new file mode 100644 (file)
index 0000000..a397d3a
--- /dev/null
@@ -0,0 +1,45 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+   <xacro:macro name="bhand_base">
+
+       <link name="bhand_origin"/>
+       
+       <link name="bhand_link_base">
+               <inertial>
+                       <mass value="0.8"/>
+                       <origin rpy="0 0 0" xyz="0 0 0" />  
+                       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry name="bhand_link_base_visual">
+                               <mesh filename="package://bhand_description/meshes/bh_base.stl" />
+                       </geometry>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry name="bhand_link_base_collision">
+                               <mesh filename="package://bhand_description/meshes/bh_base.stl" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_link_base">
+               <selfCollide>true</selfCollide>
+               <material>Gazebo/Blue</material>
+       </gazebo>
+
+
+       <joint name="bhand_base_joint" type="fixed">
+               <!--origin rpy="0 0 0" xyz="-0.060 -0.140 0.206"/-->
+               <!--origin rpy="0 0 0" xyz="0.22 0.14 0.346"/-->
+               <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
+               <child link="bhand_link_base"/>
+               <parent link="bhand_origin"/>
+       </joint>
+
+    </xacro:macro>
+
+</robot>
diff --git a/bhand_description/xacro/bhand_finger.urdf.xacro b/bhand_description/xacro/bhand_finger.urdf.xacro
new file mode 100644 (file)
index 0000000..e8b7e88
--- /dev/null
@@ -0,0 +1,60 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="bhand_finger" params="parent joint type *origin *limit *mesh">
+
+       <link name="bhand_link${joint}">
+               <inertial>
+                       <mass value="0.1"/>
+                       <origin xyz="0 0 0" />  
+                       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry name="link_bhand_f${joint}_visual">
+                               <xacro:insert_block name="mesh" />
+                       </geometry>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry name="link_bhand_f${joint}_collision">
+                               <xacro:insert_block name="mesh" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_link${joint}">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo> 
+
+
+       <joint name="bhand_j${joint}_joint" type="${type}">
+               <!--origin xyz="-0.02475 0.0 0.0395" rpy="0.0 0 1.57079633" /--> 
+               <!--origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /--> 
+
+               <xacro:insert_block name="origin" />
+
+               <parent link="${parent}"/>
+               <child link="bhand_link${joint}" />
+               <axis xyz="0 0 1"/>
+
+               <xacro:insert_block name="limit" />
+
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint >
+
+       <transmission type="pr2_mechanism_model/SimpleTransmission" name="f${joint}_transmission">
+               <actuator name="bhand_link${joint}" />
+               <joint name="bhand_f${joint}_joint" />
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+
+  </xacro:macro>
+
+</robot>
diff --git a/plier_description/launch/display.launch b/plier_description/launch/display.launch
new file mode 100644 (file)
index 0000000..a113ced
--- /dev/null
@@ -0,0 +1,11 @@
+<launch>\r
+  <arg name="model" />\r
+  <arg name="gui" default="False" />\r
+  <param\r
+    name="robot_description"\r
+    textfile="$(find plier_description)/urdf/plier.urdf" />\r
+  <param name="use_gui" value="$(arg gui)" />\r
+  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />\r
+  <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />\r
+  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find plier_description)/urdf.rviz" />\r
+</launch>
\ No newline at end of file
diff --git a/plier_description/launch/gazebo.launch b/plier_description/launch/gazebo.launch
new file mode 100644 (file)
index 0000000..c829339
--- /dev/null
@@ -0,0 +1,7 @@
+<launch>\r
+  <include file="$(find gazebo_worlds)/launch/empty_world.launch" />\r
+  <node name="tf_footprint_base" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 base_link base_footprint 40" />\r
+  <node name="spawn_model" pkg="gazebo" type="spawn_model" args="-file $(find plier)/urdf/plier.urdf -urdf -model plier" output="screen" />\r
+  <include file="$(find pr2_controller_manager)/controller_manager.launch" />\r
+  <node name="fake_joint_calibration" pkg="rostopic" type="rostopic"  args="pub /calibrated std_msgs/Bool true" />\r
+</launch>
\ No newline at end of file
diff --git a/plier_description/launch/plier.launch b/plier_description/launch/plier.launch
new file mode 100644 (file)
index 0000000..8376d88
--- /dev/null
@@ -0,0 +1,4 @@
+<launch>
+       <param name="robot_description" textfile="$(find plier_description)/urdf/plier.urdf" />
+       <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model plier" respawn="false" output="screen" />
+</launch>
diff --git a/plier_description/launch/plier_sim.launch b/plier_description/launch/plier_sim.launch
new file mode 100644 (file)
index 0000000..c9bf77f
--- /dev/null
@@ -0,0 +1,6 @@
+<launch>
+       <!-- Start Gazebo -->
+       <include file="$(find gazebo_worlds)/launch/empty_world.launch"/>
+
+       <include file="$(find plier_description)/launch/plier.launch"/>
+</launch>
diff --git a/plier_description/manifest.xml b/plier_description/manifest.xml
new file mode 100644 (file)
index 0000000..97a62e2
--- /dev/null
@@ -0,0 +1,6 @@
+<package>\r
+  <description brief="plier_description">plier_description</description>\r
+  <depend package="gazebo" />\r
+  <author>Walter Fetter Lags</author>\r
+  <license>BSD</license>\r
+</package>
\ No newline at end of file
diff --git a/plier_description/meshes/base_link.stl b/plier_description/meshes/base_link.stl
new file mode 100644 (file)
index 0000000..eab1cf1
Binary files /dev/null and b/plier_description/meshes/base_link.stl differ
diff --git a/plier_description/meshes/link1.stl b/plier_description/meshes/link1.stl
new file mode 100644 (file)
index 0000000..6bcdc08
Binary files /dev/null and b/plier_description/meshes/link1.stl differ
diff --git a/plier_description/meshes/link2.stl b/plier_description/meshes/link2.stl
new file mode 100644 (file)
index 0000000..6f95350
Binary files /dev/null and b/plier_description/meshes/link2.stl differ
diff --git a/plier_description/urdf/plier.urdf b/plier_description/urdf/plier.urdf
new file mode 100644 (file)
index 0000000..6ad1514
--- /dev/null
@@ -0,0 +1,112 @@
+<robot name="plier">\r
+\r
+  <link name="base_link">\r
+\r
+    <inertial>\r
+      <origin xyz="-2.9946E-09 2.3647E-09 0.038028" rpy="0 0 0" />\r
+      <mass value="0.065887" />\r
+      <inertia ixx="0.0001476" ixy="5.724E-13" ixz="-6.0829E-11" iyy="0.0001476" iyz="4.4824E-11" izz="8.4481E-05" />\r
+    </inertial>\r
+\r
+    <visual>\r
+      <origin  xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/base_link.stl" />\r
+      </geometry>\r
+      <material name="">\r
+        <color rgba="0.75294 0.75294 0.75294 1" />\r
+      </material>\r
+    </visual>\r
+\r
+    <collision>\r
+      <origin xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/base_link.stl" />\r
+      </geometry>\r
+    </collision>\r
+  </link>\r
+\r
+  <link name="link1">\r
+\r
+    <inertial>\r
+      <origin xyz="0.00018812 -0.011115 0.0015573" rpy="0 0 0" />\r
+      <mass value="0.00011808" />\r
+      <inertia ixx="5.1612E-09" ixy="-9.0621E-11" ixz="2.0497E-12" iyy="1.6125E-10" iyz="-1.1473E-10" izz="5.0583E-09" />\r
+    </inertial>\r
+\r
+    <visual>\r
+      <origin xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/link1.stl" />\r
+      </geometry>\r
+      <material name="">\r
+        <color rgba="0.75294 0.75294 0.75294 1" />\r
+      </material>\r
+    </visual>\r
+\r
+    <collision>\r
+      <origin xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/link1.stl" />\r
+      </geometry>\r
+    </collision>\r
+\r
+  </link>\r
+\r
+  <joint name="joint1" type="revolute">\r
+    <origin xyz="-0.00125 0.00098997 0.3459" rpy="-1.5708 -6.123E-17 -1.5708" />\r
+    <parent link="base_link" />\r
+    <child link="link1" />\r
+    <axis xyz="0 0 1" />\r
+    <limit lower="-0.05" upper="0.05" effort="0.31" velocity="0.25" />\r
+  </joint>\r
+\r
+  <link name="link2">\r
+    <inertial>\r
+      <origin xyz="-0.0001883 -0.011122 0.00021282" rpy="0 0 0" />\r
+      <mass value="0.00011791" />\r
+      <inertia ixx="5.1222E-09" ixy="9.017E-11" ixz="1.1618E-12" iyy="1.4783E-10" iyz="6.6059E-11" izz="5.0326E-09" />\r
+    </inertial>\r
+\r
+    <visual>\r
+      <origin xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/link2.stl" />\r
+      </geometry>\r
+      <material name="">\r
+        <color rgba="0.75294 0.75294 0.75294 1" />\r
+      </material>\r
+    </visual>\r
+\r
+    <collision>\r
+      <origin xyz="0 0 0" rpy="0 0 0" />\r
+      <geometry>\r
+        <mesh filename="package://plier_description/meshes/link2.stl" />\r
+      </geometry>\r
+    </collision>\r
+\r
+  </link>\r
+\r
+  <joint name="joint2" type="revolute">\r
+    <origin xyz="0.00025 -0.00098997 0.3459" rpy="-1.5708 -6.123E-17 -1.5708" />\r
+    <parent link="base_link" />\r
+    <child link="link2" />\r
+    <axis xyz="0 0 1" />\r
+    <limit lower="-0.05" upper="0.05" effort="0.31" velocity="0.25" />\r
+  </joint>\r
+\r
+  <gazebo reference="base_link">
+    <material>Gazebo/Yellow</material>
+  </gazebo>\r
+\r
+\r
+  <gazebo reference="link1">
+    <material>Gazebo/White</material>
+  </gazebo>\r
+\r
+\r
+  <gazebo reference="link2">
+    <material>Gazebo/Grey</material>
+  </gazebo>\r
+\r
+</robot>\r
diff --git a/stack.xml b/stack.xml
new file mode 100644 (file)
index 0000000..c3783ed
--- /dev/null
+++ b/stack.xml
@@ -0,0 +1,9 @@
+<stack>
+  <description brief="ufrgs_wam">UFRGS WAM</description>
+  <author>Maintained by Walter Fetter Lages</author>
+  <license>GNU</license>  
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/ufrgs_wam</url>
+  <depend stack="ros" />
+
+</stack>
diff --git a/wam_control_gazebo/CMakeLists.txt b/wam_control_gazebo/CMakeLists.txt
new file mode 100644 (file)
index 0000000..97ce471
--- /dev/null
@@ -0,0 +1,33 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type.  Options are:
+#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
+#  Debug          : w/ debug symbols, w/o optimization
+#  Release        : w/o debug symbols, w/ optimization
+#  RelWithDebInfo : w/ debug symbols, w/ optimization
+#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rosbuild_init()
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#rosbuild_genmsg()
+#uncomment if you have defined services
+#rosbuild_gensrv()
+
+#common commands for building c++ executables and libraries
+#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rosbuild_add_boost_directories()
+#rosbuild_link_boost(${PROJECT_NAME} thread)
+#rosbuild_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
+
+# Build RobotSim Interface
+rosbuild_add_library(wam_control_gazebo src/robot_sim_wam.cpp)
diff --git a/wam_control_gazebo/Makefile b/wam_control_gazebo/Makefile
new file mode 100644 (file)
index 0000000..b75b928
--- /dev/null
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
diff --git a/wam_control_gazebo/mainpage.dox b/wam_control_gazebo/mainpage.dox
new file mode 100644 (file)
index 0000000..590fcdc
--- /dev/null
@@ -0,0 +1,14 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b twil_control_gazebo 
+
+<!-- 
+Provide an overview of your package.
+-->
+
+-->
+
+
+*/
diff --git a/wam_control_gazebo/manifest.xml b/wam_control_gazebo/manifest.xml
new file mode 100644 (file)
index 0000000..b8569ea
--- /dev/null
@@ -0,0 +1,23 @@
+<package>
+  <description brief="wam_control_gazebo">
+
+     wam_control_gazebo
+
+  </description>
+  <author>Walter Fetter Lages</author>
+  <license>GPL</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/wam_control_gazebo</url>
+
+  <depend package="ros_control_gazebo"/>
+  <depend package="ros_control_gazebo_plugin"/>
+  
+  <depend package="wam_description"/>
+
+  <depend package="gazebo"/>
+
+  <export>
+    <ros_control_gazebo plugin="${prefix}/robot_sim_plugins.xml" />
+  </export>
+
+</package>
diff --git a/wam_control_gazebo/robot_sim_plugins.xml b/wam_control_gazebo/robot_sim_plugins.xml
new file mode 100644 (file)
index 0000000..d52e012
--- /dev/null
@@ -0,0 +1,12 @@
+<library path="lib/libwam_control_gazebo">
+
+  <class
+    name="wam_control_gazebo/RobotSimWam"
+    type="wam_control_gazebo::RobotSimWam"
+    base_class_type="ros_control_gazebo::RobotSim">
+    <description>
+      A ROS/Gazebo interface for Barrett WAM, exporting a joint_state_interface and a
+      joint_effort_interface.
+    </description>
+  </class>
+</library>
diff --git a/wam_control_gazebo/src/robot_sim_wam.cpp b/wam_control_gazebo/src/robot_sim_wam.cpp
new file mode 100644 (file)
index 0000000..5eead8e
--- /dev/null
@@ -0,0 +1,102 @@
+#include <pluginlib/class_list_macros.h>
+
+#include <hardware_interface/joint_command_interface.h>
+#include <hardware_interface/robot_hw.h>
+
+#include <ros_control_gazebo/robot_sim.h>
+
+#include <angles/angles.h>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/common/common.hh>
+
+namespace wam_control_gazebo
+{
+
+  class RobotSimWam:public ros_control_gazebo::RobotSim
+  {
+  
+    unsigned int n_dof_;
+
+    hardware_interface::JointStateInterface js_interface_;
+    hardware_interface::EffortJointInterface ej_interface_;
+
+    std::vector<std::string> joint_name_;
+    std::vector<double> joint_position_;
+    std::vector<double> joint_velocity_;
+    std::vector<double> joint_effort_;
+    std::vector<double> joint_effort_command_;
+
+    std::vector<gazebo::physics::JointPtr> sim_joints_;
+    
+    public:
+    
+    RobotSimWam(void):n_dof_(7),joint_name_(n_dof_),joint_position_(n_dof_),
+      joint_velocity_(n_dof_),joint_effort_(n_dof_),joint_effort_command_(n_dof_)
+    {
+
+      joint_name_[0]="wam_joint_1";
+      joint_name_[1]="wam_joint_2";
+      joint_name_[2]="wam_joint_3";
+      joint_name_[3]="wam_joint_4";
+      joint_name_[4]="wam_joint_5";
+      joint_name_[5]="wam_joint_6";
+      joint_name_[6]="wam_joint_7";
+      
+      for(unsigned int j=0;j < n_dof_;j++)
+      {
+        joint_position_[j]=0.0;
+        joint_velocity_[j]=0.0;
+        joint_effort_[j]=0.0;
+        
+        joint_effort_command_[j] = 0.0;
+
+        js_interface_.registerJoint(joint_name_[j],&joint_position_[j],&joint_velocity_[j],&joint_effort_[j]);
+        ej_interface_.registerJoint(js_interface_.getJointStateHandle(joint_name_[j]),&joint_effort_command_[j]);
+      }
+
+      registerInterface(&js_interface_);
+      registerInterface(&ej_interface_);
+    }
+
+
+    bool initSim(ros::NodeHandle nh,gazebo::physics::ModelPtr model)
+    {
+      for(unsigned int j=0;j < n_dof_;j++)
+      {
+        ROS_INFO_STREAM("Getting pointer to gazebo joint: " << joint_name_[j]);
+        gazebo::physics::JointPtr joint=model->GetJoint(joint_name_[j]);
+        if(joint) sim_joints_.push_back(joint);
+        else
+        {
+          ROS_ERROR_STREAM("This robot has a joint named \"" << joint_name_[j]
+              <<"\" which is not in the gazebo model.");
+          return false;
+        }
+      }
+      return true;
+    }
+
+    void readSim(ros::Time time,ros::Duration period)
+    {
+      for(unsigned int j=0; j < n_dof_;j++)
+      {
+//        joint_position_[j]+=angles::shortest_angular_distance
+//          (joint_position_[j],sim_joints_[j]->GetAngle(0).GetAsRadian());
+        joint_position_[j]=sim_joints_[j]->GetAngle(0).GetAsRadian();
+        joint_velocity_[j]=sim_joints_[j]->GetVelocity(0);
+//        joint_effort_[j]=sim_joints_[j]->GetForce(0u);
+        joint_effort_[j]=joint_effort_command_[j];
+      }
+    }
+
+    void writeSim(ros::Time time,ros::Duration period) 
+    {
+      for(unsigned int j=0;j < n_dof_;j++) sim_joints_[j]->SetForce(0,joint_effort_command_[j]);
+    }
+
+  };
+}
+
+PLUGINLIB_DECLARE_CLASS(wam_control_gazebo,RobotSimWam,wam_control_gazebo::RobotSimWam,ros_control_gazebo::RobotSim)
diff --git a/wam_controllers/CMakeLists.txt b/wam_controllers/CMakeLists.txt
new file mode 100644 (file)
index 0000000..95ad1f8
--- /dev/null
@@ -0,0 +1,30 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type.  Options are:
+#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
+#  Debug          : w/ debug symbols, w/o optimization
+#  Release        : w/o debug symbols, w/ optimization
+#  RelWithDebInfo : w/ debug symbols, w/ optimization
+#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rosbuild_init()
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#rosbuild_genmsg()
+#uncomment if you have defined services
+#rosbuild_gensrv()
+
+#common commands for building c++ executables and libraries
+rosbuild_add_library(${PROJECT_NAME} src/computed_torque_controller.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rosbuild_add_boost_directories()
+#rosbuild_link_boost(${PROJECT_NAME} thread)
+#rosbuild_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
diff --git a/wam_controllers/Makefile b/wam_controllers/Makefile
new file mode 100644 (file)
index 0000000..b75b928
--- /dev/null
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
diff --git a/wam_controllers/README b/wam_controllers/README
new file mode 100644 (file)
index 0000000..b29cdbe
--- /dev/null
@@ -0,0 +1,10 @@
+To publish reference:
+
+rostopic pub /wam/computed_torque_controller/command trajectory_msgs/JointTrajectoryPoint "[0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]"
+
+Arguments are positions, velocities, accelerations, time from start in
+seconds and nanoseconds.
+
+Set starting position:
+
+rosservice call /gazebo/set_model_configuration wam joint ['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4','wam_joint_5','wam_joint_6','wam_joint_7'] [0.0,0.75,0.0,1.5,0.0,0.9,0.0]
\ No newline at end of file
diff --git a/wam_controllers/config/computed_torque_control.yaml b/wam_controllers/config/computed_torque_control.yaml
new file mode 100644 (file)
index 0000000..a1e546f
--- /dev/null
@@ -0,0 +1,16 @@
+wam:
+
+    joint_state_controller:
+      type: joint_state_controller/JointStateController
+      publish_rate: 100
+
+    computed_torque_controller:
+      type: wam_controllers/ComputedTorqueController
+      joints:
+        - wam_joint_1
+        - wam_joint_2
+        - wam_joint_3
+        - wam_joint_4
+        - wam_joint_5
+        - wam_joint_6
+        - wam_joint_7
diff --git a/wam_controllers/doc/urdf2kdl.txt b/wam_controllers/doc/urdf2kdl.txt
new file mode 100644 (file)
index 0000000..0f5af05
--- /dev/null
@@ -0,0 +1,9 @@
+KDL specifies the inertia in the reference frame of the link, the URDF
+ specifies the inertia in the inertia reference frame.
+
+A KDL segment is an ideal rigid body to which one single Joint is connected
+and one single tip frame.  It contains:
+
+- a Joint located at the root frame of the Segment.
+- a Frame describing the pose between the end of the Joint and the tip
+frame of the Segment.
diff --git a/wam_controllers/include/wam_controllers/computed_torque_controller.h b/wam_controllers/include/wam_controllers/computed_torque_controller.h
new file mode 100644 (file)
index 0000000..60a09ea
--- /dev/null
@@ -0,0 +1,61 @@
+#ifndef WAM_CONTROLLERS_COMPUTED_TORQUE_CONTROLLER_H
+#define WAM_CONTROLLERS_COMPUTED_TORQUE_CONTROLLER_H
+
+#include <cstddef>
+#include <vector>
+#include <string>
+
+#include <ros/node_handle.h>
+#include <hardware_interface/joint_command_interface.h>
+#include <controller_interface/controller.h>
+#include <trajectory_msgs/JointTrajectoryPoint.h>
+#include <sensor_msgs/JointState.h>
+
+#include <Eigen/Core>
+
+#include <kdl/frames.hpp>
+#include <kdl_parser/kdl_parser.hpp>
+#include <kdl/chainidsolver_recursive_newton_euler.hpp>
+
+
+namespace wam_controllers
+{
+       class ComputedTorqueController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
+       {
+               public:
+                       ComputedTorqueController(void);
+                       ~ComputedTorqueController(void);
+               
+                       bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n);
+                       void starting(const ros::Time& time);
+                       void update(const ros::Time& time);
+                               
+               private:
+                       ros::NodeHandle node_;
+                       ros::Time last_time_;
+                       hardware_interface::EffortJointInterface *robot_;
+                       std::vector<hardware_interface::JointHandle> joints_;
+               
+                       void commandCB(const trajectory_msgs::JointTrajectoryPoint::ConstPtr &referencePoint);
+                       ros::Subscriber sub_command_;
+                       
+                       KDL::ChainIdSolver_RNE *idsolver;
+                               
+                       KDL::JntArray q;
+                       KDL::JntArray dq;
+                       KDL::JntArray ddq;
+                       
+                       KDL::JntArray qr;
+                       KDL::JntArray dqr;
+                       KDL::JntArray ddqr;
+                       
+                       KDL::JntArray torque;
+               
+                       KDL::Wrenches fext;
+                       
+                       Eigen::MatrixXd Kp;
+                       Eigen::MatrixXd Kd;
+                       
+       };
+}
+#endif
diff --git a/wam_controllers/launch/computed_torque.launch b/wam_controllers/launch/computed_torque.launch
new file mode 100644 (file)
index 0000000..2da9e12
--- /dev/null
@@ -0,0 +1,14 @@
+<launch>
+               <arg name="paused" default="true"/>
+
+       <include file="$(find wam_description)/launch/wam_sim.launch">
+               <arg name="paused" value="$(arg paused)"/>
+       </include>
+
+       <rosparam file="$(find wam_controllers)/config/computed_torque_control.yaml" command="load"/>
+
+       <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+               output="screen" ns="/wam" args="joint_state_controller computed_torque_controller"/>
+
+       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+</launch>
diff --git a/wam_controllers/launch/computed_torque_table.launch b/wam_controllers/launch/computed_torque_table.launch
new file mode 100644 (file)
index 0000000..3975bd5
--- /dev/null
@@ -0,0 +1,14 @@
+<launch>
+               <arg name="paused" default="true"/>
+
+       <include file="$(find wam_description)/launch/wam_table_sim.launch">
+               <arg name="paused" value="$(arg paused)"/>
+       </include>
+
+       <rosparam file="$(find wam_controllers)/config/computed_torque_control.yaml" command="load"/>
+
+       <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+               output="screen" ns="/wam" args="joint_state_controller computed_torque_controller"/>
+
+       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+</launch>
diff --git a/wam_controllers/mainpage.dox b/wam_controllers/mainpage.dox
new file mode 100644 (file)
index 0000000..deb448e
--- /dev/null
@@ -0,0 +1,14 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b twil_controllers 
+
+<!-- 
+Provide an overview of your package.
+-->
+
+-->
+
+
+*/
diff --git a/wam_controllers/manifest.xml b/wam_controllers/manifest.xml
new file mode 100644 (file)
index 0000000..2fd288c
--- /dev/null
@@ -0,0 +1,25 @@
+<package>
+  <description brief="wam_controllers">
+
+     wam_controllers
+
+  </description>
+  <author>Walter Fetter Lages</author>
+  <license>GPL</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/wam_controllers</url>
+  <depend package="joint_state_controller"/>
+  <!--depend package="effort_controllers"/-->
+  <depend package="wam_control_gazebo"/>
+  <depend package="controller_interface"/>
+  <depend package="orocos_kdl"/>
+  <depend package="kdl_parser"/>
+  <depend package="trajectory_msgs"/>
+
+  <export>
+    <controller_interface plugin="${prefix}/wam_controllers_plugins.xml"/>
+  </export>
+      
+</package>
+
+
diff --git a/wam_controllers/src/computed_torque_controller.cpp b/wam_controllers/src/computed_torque_controller.cpp
new file mode 100644 (file)
index 0000000..407a982
--- /dev/null
@@ -0,0 +1,173 @@
+#include <wam_controllers/computed_torque_controller.h>
+#include <pluginlib/class_list_macros.h>
+
+#include <kdl/frames.hpp>
+#include <kdl_parser/kdl_parser.hpp>
+#include <kdl/chainidsolver_recursive_newton_euler.hpp>
+
+#define Ts 5.0
+#define Xi 1.0
+#define Wn (4.0/Ts/Xi)
+
+
+namespace wam_controllers
+{      
+       ComputedTorqueController::ComputedTorqueController(void):
+               q(0),dq(0),ddq(0),qr(0),dqr(0),ddqr(0),torque(0),fext(0)
+       {
+       }
+       
+       ComputedTorqueController::~ComputedTorqueController(void)
+       {
+               sub_command_.shutdown();
+       }
+               
+       bool ComputedTorqueController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
+       {
+               node_=n;
+               robot_=robot;
+               
+               XmlRpc::XmlRpcValue joint_names;
+               if(!node_.getParam("joints",joint_names))
+               {
+                       ROS_ERROR("No 'joints'  parameter in controller. (namespace: %s)",node_.getNamespace().c_str());
+                       return false;
+               }
+               
+               if(joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
+               {
+                       ROS_ERROR("The 'joints' parameter is not a struct. (namespace: %s)",node_.getNamespace().c_str());
+                       return false;
+               }
+               
+               for(int i=0; i < joint_names.size();i++)
+               {
+                       XmlRpc::XmlRpcValue &name_value=joint_names[i];
+                       if(name_value.getType() != XmlRpc::XmlRpcValue::TypeString)
+                       {
+                               ROS_ERROR("Array of joint names should contain only strings. (namespace: %s)",node_.getNamespace().c_str());
+                               return false;
+                       }
+                       
+                       hardware_interface::JointHandle j=robot->getJointHandle((std::string)name_value);
+                       joints_.push_back(j);
+               }
+               sub_command_ = node_.subscribe("command",1000,&ComputedTorqueController::commandCB, this);
+               
+               std::string robot_desc_string;
+               if(!node_.getParam("/robot_description",robot_desc_string))
+                {
+                       ROS_ERROR("Could not find '/robot_description'.");
+                       return false;
+               }
+               
+               KDL::Tree tree;
+               if (!kdl_parser::treeFromString(robot_desc_string,tree))
+               {
+                       ROS_ERROR("Failed to construct KDL tree.");
+                       return false;
+               }
+               
+               KDL::Chain chain;
+               if (!tree.getChain("wam_origin","wam_tool_plate",chain)) 
+               {
+                       ROS_ERROR("Failed to get chain from KDL tree.");
+                       return false;
+               }
+               
+               // Get gravity from gazebo or set values if not simulating
+               KDL::Vector g;
+               node_.param("/gazebo/gravity_x",g[0],0.0);
+               node_.param("/gazebo/gravity_y",g[1],0.0);
+               node_.param("/gazebo/gravity_z",g[2],-9.8);
+
+               if((idsolver=new KDL::ChainIdSolver_RNE(chain,g)) == NULL)
+               {
+                       ROS_ERROR("Failed to create ChainIDSolver_RNE.");
+                       return false;
+               }
+
+                // set vectors to the right size
+               q.resize(chain.getNrOfJoints());
+               dq.resize(chain.getNrOfJoints());
+               ddq.resize(chain.getNrOfJoints());
+               qr.resize(chain.getNrOfJoints());
+               dqr.resize(chain.getNrOfJoints());
+               ddqr.resize(chain.getNrOfJoints());
+               torque.resize(chain.getNrOfJoints());
+
+               fext.resize(chain.getNrOfSegments());
+               
+               Kp.resize(chain.getNrOfJoints(),chain.getNrOfJoints());
+               Kd.resize(chain.getNrOfJoints(),chain.getNrOfJoints());
+               
+               return true;
+       }
+       
+       void ComputedTorqueController::starting(const ros::Time& time)
+       {
+               last_time_=time;
+               Kp.setZero();
+               Kd.setZero();
+               for(unsigned int i=0; i < joints_.size();i++)
+               {
+                       q(i)=joints_[i].getPosition();
+                       dq(i)=joints_[i].getVelocity();
+                       Kp(i,i)=Wn*Wn;
+                       Kd(i,i)=2.0*Xi*Wn;
+               }
+                qr=q;
+                dqr=dq;
+               SetToZero(ddqr);
+       }
+       
+       void ComputedTorqueController::update(const ros::Time& time)
+       {
+               ros::Duration dt=time-last_time_;
+               last_time_=time;
+               
+               for(unsigned int i=0;i < joints_.size();i++)
+               {
+                       q(i)=joints_[i].getPosition();
+                       dq(i)=joints_[i].getVelocity();
+               }
+               
+               for(unsigned int i=0;i < fext.size();i++) fext[i].Zero();
+               
+               ddq.data=ddqr.data+Kp*(qr.data-q.data)+Kd*(dqr.data-dq.data);
+
+/*             std::cout << "time=" << time.toSec() << std::endl;
+               
+               for(unsigned int i=0;i < joints_.size();i++)
+               {
+                       std::cout << "q[" << i << "]=" << q(i)
+                               << "\tqr[" << i << "]=" << qr(i) << std::endl;
+                                                       
+                       std::cout << "dq[" << i << "]=" << dq(i)
+                               << "\tdqr[" << i << "]=" << dqr(i) << std::endl;
+               
+
+                       std::cout << "ddq[" << i << "]=" << ddq(i)
+                               << "\tddqr[" << i << "]=" << ddqr(i) << std::endl;
+               }
+*/             
+               // Compute linearization.
+               if(idsolver->CartToJnt(q,dq,ddq,fext,torque) < 0) ROS_ERROR("KDL inverse dynamics solver failed.");
+               
+//             for(unsigned int i=0;i < joints_.size();i++) std::cout << "torque[" << i << "]=" << torque(i) << std::endl;
+               
+               // Apply torques
+               for(unsigned int i=0;i < joints_.size();i++) joints_[i].setCommand(torque(i));
+       }
+       
+       void ComputedTorqueController::commandCB(const trajectory_msgs::JointTrajectoryPoint::ConstPtr &referencePoint)
+       {
+               for(unsigned int i=0;i < qr.rows();i++)
+               {
+                       qr(i)=referencePoint->positions[i];
+                       dqr(i)=referencePoint->velocities[i];
+                       ddqr(i)=referencePoint->accelerations[i];
+               }
+       }
+}
+PLUGINLIB_DECLARE_CLASS(wam_controllers,ComputedTorqueController,wam_controllers::ComputedTorqueController,controller_interface::ControllerBase)
diff --git a/wam_controllers/wam_controllers_plugins.xml b/wam_controllers/wam_controllers_plugins.xml
new file mode 100644 (file)
index 0000000..4be4031
--- /dev/null
@@ -0,0 +1,11 @@
+<library path="lib/libwam_controllers">
+
+  <class name="wam_controllers/ComputedTorqueController" type="wam_controllers::ComputedTorqueController" base_class_type="controller_interface::ControllerBase">
+    <description>
+      The ComputedTorqueControllers linearizes the Barrett WAM dynamic
+      model.  The linearized inputs are joint accelerations.  It expects a
+      EffortJointInterface type of hardware interface.
+    </description>
+  </class>
+
+</library>
diff --git a/wam_description/CMakeLists.txt b/wam_description/CMakeLists.txt
new file mode 100644 (file)
index 0000000..f8f1c9c
--- /dev/null
@@ -0,0 +1,30 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type.  Options are:
+#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
+#  Debug          : w/ debug symbols, w/o optimization
+#  Release        : w/o debug symbols, w/ optimization
+#  RelWithDebInfo : w/ debug symbols, w/ optimization
+#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rosbuild_init()
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#rosbuild_genmsg()
+#uncomment if you have defined services
+#rosbuild_gensrv()
+
+#common commands for building c++ executables and libraries
+#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rosbuild_add_boost_directories()
+#rosbuild_link_boost(${PROJECT_NAME} thread)
+#rosbuild_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
diff --git a/wam_description/Makefile b/wam_description/Makefile
new file mode 100644 (file)
index 0000000..b75b928
--- /dev/null
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
diff --git a/wam_description/launch/wam.launch b/wam_description/launch/wam.launch
new file mode 100644 (file)
index 0000000..e13ade7
--- /dev/null
@@ -0,0 +1,4 @@
+<launch>
+       <param name="robot_description" command="$(find xacro)/xacro.py '$(find wam_description)/xacro/wam.urdf.xacro'" />
+       <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
+</launch>
diff --git a/wam_description/launch/wam_bhand.launch b/wam_description/launch/wam_bhand.launch
new file mode 100644 (file)
index 0000000..5302c4b
--- /dev/null
@@ -0,0 +1,4 @@
+<launch>
+       <param name="robot_description" command="$(find xacro)/xacro.py '$(find wam_description)/xacro/wam_bhand.urdf.xacro'" />
+       <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
+</launch>
diff --git a/wam_description/launch/wam_bhand_sim.launch b/wam_description/launch/wam_bhand_sim.launch
new file mode 100644 (file)
index 0000000..60b4beb
--- /dev/null
@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<launch>
+       <arg name="paused" default="false"/>
+
+       <!-- Start Gazebo -->
+       <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+               <arg name="paused" value="$(arg paused)"/>
+       </include>
+
+       <include file="$(find wam_description)/launch/wam_bhand.launch"/>
+</launch>
diff --git a/wam_description/launch/wam_sim.launch b/wam_description/launch/wam_sim.launch
new file mode 100644 (file)
index 0000000..b22b8d0
--- /dev/null
@@ -0,0 +1,11 @@
+<launch>
+       <arg name="paused" default="false"/>
+
+       <!-- Start Gazebo -->
+       <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+               <arg name="paused" value="$(arg paused)"/>
+       </include>
+
+       <include file="$(find wam_description)/launch/wam.launch"/>
+
+</launch>
diff --git a/wam_description/launch/wam_table.launch b/wam_description/launch/wam_table.launch
new file mode 100644 (file)
index 0000000..fb882a6
--- /dev/null
@@ -0,0 +1,4 @@
+<launch>
+       <param name="robot_description" command="$(find xacro)/xacro.py '$(find wam_description)/xacro/wam_table.urdf.xacro'" />
+       <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
+</launch>
diff --git a/wam_description/launch/wam_table_sim.launch b/wam_description/launch/wam_table_sim.launch
new file mode 100644 (file)
index 0000000..05648af
--- /dev/null
@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<launch>
+       <arg name="paused" default="false"/>
+
+       <!-- Start Gazebo -->
+       <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+               <arg name="paused" value="$(arg paused)"/>
+       </include>
+
+       <include file="$(find wam_description)/launch/wam_table.launch"/>
+</launch>
diff --git a/wam_description/manifest.xml b/wam_description/manifest.xml
new file mode 100644 (file)
index 0000000..44032f1
--- /dev/null
@@ -0,0 +1,14 @@
+<package>
+  <description brief="wam_description">
+
+     wam_description
+
+  </description>
+  <author>Walter Fetter Lages</author>
+  <license>GNU</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/wam_description</url>
+
+</package>
+
+
diff --git a/wam_description/meshes/wam1.stl b/wam_description/meshes/wam1.stl
new file mode 100644 (file)
index 0000000..3c8a5a4
Binary files /dev/null and b/wam_description/meshes/wam1.stl differ
diff --git a/wam_description/meshes/wam2.stl b/wam_description/meshes/wam2.stl
new file mode 100644 (file)
index 0000000..0f50c93
Binary files /dev/null and b/wam_description/meshes/wam2.stl differ
diff --git a/wam_description/meshes/wam3.stl b/wam_description/meshes/wam3.stl
new file mode 100644 (file)
index 0000000..966efcc
Binary files /dev/null and b/wam_description/meshes/wam3.stl differ
diff --git a/wam_description/meshes/wam4.stl b/wam_description/meshes/wam4.stl
new file mode 100644 (file)
index 0000000..89c9de2
Binary files /dev/null and b/wam_description/meshes/wam4.stl differ
diff --git a/wam_description/meshes/wam5.stl b/wam_description/meshes/wam5.stl
new file mode 100644 (file)
index 0000000..97cb0ab
Binary files /dev/null and b/wam_description/meshes/wam5.stl differ
diff --git a/wam_description/meshes/wam6.stl b/wam_description/meshes/wam6.stl
new file mode 100644 (file)
index 0000000..e3b014a
Binary files /dev/null and b/wam_description/meshes/wam6.stl differ
diff --git a/wam_description/meshes/wam7.stl b/wam_description/meshes/wam7.stl
new file mode 100644 (file)
index 0000000..2cbf2b1
Binary files /dev/null and b/wam_description/meshes/wam7.stl differ
diff --git a/wam_description/meshes/wambase.stl b/wam_description/meshes/wambase.stl
new file mode 100644 (file)
index 0000000..f7d5132
Binary files /dev/null and b/wam_description/meshes/wambase.stl differ
diff --git a/wam_description/xacro/.wam_j1.urdf.xacro.swo b/wam_description/xacro/.wam_j1.urdf.xacro.swo
new file mode 100644 (file)
index 0000000..c20cc44
Binary files /dev/null and b/wam_description/xacro/.wam_j1.urdf.xacro.swo differ
diff --git a/wam_description/xacro/wam.urdf.xacro b/wam_description/xacro/wam.urdf.xacro
new file mode 100644 (file)
index 0000000..6fae73e
--- /dev/null
@@ -0,0 +1,50 @@
+<?xml version="1.0"?>
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+       xmlns:xacro="http://ros.org/wiki/xacro"
+       name="wam">
+  
+  <!-- LINKS   -->  
+  <include filename="$(find wam_description)/xacro/wam_base.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j1.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j2.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j3.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j4.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j5.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j6.urdf.xacro" />
+  <include filename="$(find wam_description)/xacro/wam_j7.urdf.xacro" />
+
+  <include filename="$(find wam_description)/xacro/wam_tool_plate.urdf.xacro" />
+
+  <xacro:wam_base>
+  </xacro:wam_base>
+  <xacro:wam_j1 parent="wam_link_base">
+  </xacro:wam_j1>
+  <xacro:wam_j2 parent="wam_link_1">
+  </xacro:wam_j2>
+  <xacro:wam_j3 parent="wam_link_2">
+  </xacro:wam_j3>
+  <xacro:wam_j4 parent="wam_link_3">
+  </xacro:wam_j4>
+  <xacro:wam_j5 parent="wam_link_4">
+  </xacro:wam_j5>
+  <xacro:wam_j6 parent="wam_link_5">
+  </xacro:wam_j6>
+  <xacro:wam_j7 parent="wam_link_6">
+  </xacro:wam_j7>
+  <xacro:wam_tool_plate parent="wam_link_7">
+  </xacro:wam_tool_plate>
+
+  <gazebo>
+    <controller:ros_control_gazebo_plugin
+      name="ros_control" 
+      plugin="$(find ros_control_gazebo_plugin)/lib/libros_control_gazebo_plugin.so">
+      <ns>wam</ns>
+      <robotSimType>wam_control_gazebo/RobotSimWam</robotSimType>
+      <controlPeriod>0.001</controlPeriod>
+    </controller:ros_control_gazebo_plugin>
+  </gazebo>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_base.urdf.xacro b/wam_description/xacro/wam_base.urdf.xacro
new file mode 100644 (file)
index 0000000..3091252
--- /dev/null
@@ -0,0 +1,48 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_base">
+
+       <link name="wam_origin"/>
+       
+       <link name="wam_link_base">
+               <inertial>
+                       <mass value="9.97059584"/>
+                       <origin xyz="-0.02017671 -0.26604706 -0.14071720" />
+                       <inertia ixx="1.01232865" ixy="0.05992441" ixz="0.05388736" iyy="0.38443311" iyz="0.37488748" izz="0.82739198"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry name="wam_link_base_visual">
+                               <mesh filename="package://wam_description/meshes/wambase.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="LightGrey">
+                               <color rgba="0.9 0.9 0.9 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_base_collision">
+                               <mesh filename="package://wam_description/meshes/wambase.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_base">
+               <selfCollide>true</selfCollide>
+               <material>Gazebo/Grey</material>
+       </gazebo>
+
+
+       <joint name="wam_base_joint" type="fixed">
+               <!--origin rpy="0 0 0" xyz="-0.060 -0.140 0.206"/-->
+               <origin rpy="0 0 0" xyz="0.22 0.14 0.346"/>
+               <child link="wam_link_base"/>
+               <parent link="wam_origin"/>
+       </joint>
+
+       </xacro:macro>
+
+</robot>
diff --git a/wam_description/xacro/wam_bhand.urdf.xacro b/wam_description/xacro/wam_bhand.urdf.xacro
new file mode 100644 (file)
index 0000000..f9bec07
--- /dev/null
@@ -0,0 +1,22 @@
+<?xml version="1.0"?>
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+       xmlns:xacro="http://ros.org/wiki/xacro"
+       name="wam">
+
+  <property name="M_PI" value="3.1415926535897931" />  
+  
+  <include filename="$(find wam_description)/xacro/wam.urdf.xacro" />
+
+  <include filename="$(find bhand_description)/xacro/bhand.urdf.xacro" />
+
+       <joint name="wam_tool_plate_bhand_joint" type="fixed">
+               <parent link="wam_tool_plate"/>
+               <child link="bhand_origin" />
+               <!--origin xyz="0.0 0.013 0.0" rpy="${-M_PI/2} 0.0 0.0" /-->
+               <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
+       </joint>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j1.urdf.xacro b/wam_description/xacro/wam_j1.urdf.xacro
new file mode 100644 (file)
index 0000000..556b2b7
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j1" params="parent">
+
+       <link name="wam_link_1">
+               <inertial>
+                       <mass value="10.76768767"/>
+                       <origin xyz="-0.00443422 0.12189039 -0.00066489" />
+                       <inertia ixx="0.29486350" ixy="-0.00795023" ixz="-0.00009311" iyy="0.11350017" iyz="0.00018711" izz="0.25065343"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_1_visual">
+                               <mesh filename="package://wam_description/meshes/wam1.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_j1_collision">
+                               <mesh filename="package://wam_description/meshes/wam1.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_1">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_1" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_1"/>
+               <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="30" lower="-2.6" upper="2.6" velocity="2.0"/>
+               <!-- <safety_controller k_velocity="0.5"/> -->
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j1_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j1"/>
+               <joint name="wam_joint_1"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
diff --git a/wam_description/xacro/wam_j2.urdf.xacro b/wam_description/xacro/wam_j2.urdf.xacro
new file mode 100644 (file)
index 0000000..0e67dcc
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j2" params="parent">
+
+       <link name="wam_link_2">
+               <inertial>
+                       <mass value="3.87493756"/>
+                       <origin xyz="-0.00236983 0.03105614 0.01542114" />
+                       <inertia ixx="0.02606840" ixy="-0.00001346" ixz="-0.00011701" iyy="0.01472202" iyz="0.00003659" izz="0.01934814"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_2_visual">
+                               <mesh filename="package://wam_description/meshes/wam2.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_2_collision">
+                               <mesh filename="package://wam_description/meshes/wam2.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_2">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_2" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_2"/>
+               <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+               <axis xyz="0 1 0"/>
+               <limit effort="30" lower="-2.0" upper="2.0" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j2_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j2"/>
+               <joint name="wam_joint_2"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j3.urdf.xacro b/wam_description/xacro/wam_j3.urdf.xacro
new file mode 100644 (file)
index 0000000..40973a7
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j3" params="parent">
+
+       <link name="wam_link_3">
+               <inertial>
+                       <mass value="1.80228141"/>
+                       <origin xyz="-0.03825858 0.20750770 0.00003309" />
+                       <inertia ixx="0.13671601" ixy="-0.01680434" ixz="0.00000510" iyy="0.00588354" iyz="-0.00000530" izz="0.13951371"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_3_visual">
+                               <mesh filename="package://wam_description/meshes/wam3.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_3_collision">
+                               <mesh filename="package://wam_description/meshes/wam3.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_3">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_3" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_3"/>
+               <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="30" lower="-2.8" upper="2.8" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j3_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j3"/>
+               <joint name="wam_joint_3"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j4.urdf.xacro b/wam_description/xacro/wam_j4.urdf.xacro
new file mode 100644 (file)
index 0000000..c357a29
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j4" params="parent">
+
+       <link name="wam_link_4">
+               <inertial>
+                       <mass value="1.06513649"/>
+                       <origin xyz="0.01095471 -0.00002567 0.14053900" />
+                       <inertia ixx="0.03952350" ixy="0.00000189" ixz="0.00003117" iyy="0.04008214" iyz="0.00000131" izz="0.00210299"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_4_visual">
+                               <mesh filename="package://wam_description/meshes/wam4.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_4_collision">
+                               <mesh filename="package://wam_description/meshes/wam4.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+               <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_4">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_4" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_4"/>
+               <origin rpy="-1.57079632679 0 0" xyz="0.045 0.0 0.55"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="35" lower="-0.9" upper="2.8" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j4_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j4"/>
+               <joint name="wam_joint_4"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j5.urdf.xacro b/wam_description/xacro/wam_j5.urdf.xacro
new file mode 100644 (file)
index 0000000..8a31b40
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j5" params="parent">
+
+       <link name="wam_link_5">
+               <inertial>
+                       <mass value="0.12376019"/>
+                       <origin xyz="0.00008921 0.00511217 0.00435824" />
+                       <inertia ixx="0.00005587" ixy="0.00000026" ixz="0.00000000" iyy="0.00007817" iyz="-0.00000083" izz="0.00006594"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_5_visual">
+                               <mesh filename="package://wam_description/meshes/wam5.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_5_collision">
+                               <mesh filename="package://wam_description/meshes/wam5.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_5">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_5" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_5"/>
+               <origin rpy="1.57079632679 0 0" xyz="-0.045 -0.3 0.0"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="30" lower="-4.8" upper="1.3" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j5_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j5"/>
+               <joint name="wam_joint_5"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j6.urdf.xacro b/wam_description/xacro/wam_j6.urdf.xacro
new file mode 100644 (file)
index 0000000..e40a5e1
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j6" params="parent">
+
+       <link name="wam_link_6">
+               <inertial>
+                       <mass value="0.41797364"/>
+                       <origin xyz="-0.00012262 -0.01703194 0.02468336" />
+                       <inertia ixx="0.00093106" ixy="0.00000148" ixz="-0.00000201" iyy="0.00049833" iyz="-0.00022162" izz="0.00057483"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_6_visual">
+                               <mesh filename="package://wam_description/meshes/wam6.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_6_collision">
+                               <mesh filename="package://wam_description/meshes/wam6.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_6">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_6" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_6"/>
+               <origin rpy="-1.57079632679 0 0" xyz="0.0 0.0 0.0"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="30" lower="-1.6" upper="1.6" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j6_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j6"/>
+               <joint name="wam_joint_6"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_j7.urdf.xacro b/wam_description/xacro/wam_j7.urdf.xacro
new file mode 100644 (file)
index 0000000..246a7a3
--- /dev/null
@@ -0,0 +1,56 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="wam_j7" params="parent">
+
+       <link name="wam_link_7">
+               <inertial>
+                       <mass value="0.06864753"/>
+                       <origin xyz="-0.00007974 0.00016313 -0.00323552" />
+                       <inertia ixx="0.00003845" ixy="-0.00000019" ixz="0.00000002" iyy="0.00003878" iyz="-0.00000004" izz="0.00007408"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_7_visual">
+                               <mesh filename="package://wam_description/meshes/wam7.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.75 0.75 0.75 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+                       <geometry name="wam_link_7_collision">
+                               <mesh filename="package://wam_description/meshes/wam7.stl" scale="1.0 1.0 1.0"/>
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>
+
+       <gazebo reference="wam_link_7">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo>
+
+       <joint name="wam_joint_7" type="revolute">
+               <parent link="${parent}"/>
+               <child link="wam_link_7"/>
+               <origin rpy="1.57079632679 0 0" xyz="0.0 0.0 0.0"/>
+               <axis xyz="0 0 1"/>
+               <limit effort="30" lower="-2.2" upper="2.2" velocity="2.0"/>
+               <joint_properties damping="100.0" friction="1000.0" />
+               <dynamics damping="1000"/>
+       </joint>
+
+       <transmission name="j7_transmission" type="pr2_mechanism_model/SimpleTransmission">
+               <actuator name="j7"/>
+               <joint name="wam_joint_7"/>
+               <mechanicalReduction>1</mechanicalReduction>
+               <motorTorqueConstant>1</motorTorqueConstant>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_table.urdf.xacro b/wam_description/xacro/wam_table.urdf.xacro
new file mode 100644 (file)
index 0000000..ddb7493
--- /dev/null
@@ -0,0 +1,30 @@
+<?xml version="1.0"?>
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+       xmlns:xacro="http://ros.org/wiki/xacro"
+       name="wam">
+
+       <property name="M_PI" value="3.1415926535897931" />
+
+       <link name="world" />
+
+       <include filename="$(find gazebo_worlds)/objects/table.urdf.xacro" />
+
+       <joint name="world_table_joint" type="fixed" static="true">
+               <parent link="world"/>
+               <child link="table_top_link" />
+               <origin xyz="${-table_x} ${-table_y} ${-table_z}" rpy="0.0 0.0 0.0" />
+       </joint>
+
+  
+       <include filename="$(find wam_description)/xacro/wam.urdf.xacro" />
+
+       <joint name="table_wam_joint" type="fixed" static="true">
+               <parent link="table_top_link"/>
+               <child link="wam_origin" />
+               <origin xyz="${(1.0-0.220)} -0.140 ${table_height}" rpy="0.0 0.0 0.0" />
+       </joint>
+
+</robot>
+
diff --git a/wam_description/xacro/wam_tool_plate.urdf.xacro b/wam_description/xacro/wam_tool_plate.urdf.xacro
new file mode 100644 (file)
index 0000000..1530ea9
--- /dev/null
@@ -0,0 +1,45 @@
+<?xml version="1.0"?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+<property name="M_PI" value="3.1415926535897931" />
+
+  <xacro:macro name="wam_tool_plate" params="parent">
+
+    <link name="wam_tool_plate">
+        <inertial>
+            <mass value="0.0001" />
+            <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
+        </inertial>
+        <visual>
+            <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
+            <geometry name="wam_tool_plate_visual">
+              <box size="0.001 0.001 0.001" />
+            </geometry>
+            <material name="Grey" >
+                <color rgba="0.75 0.75 0.75 1.0"/>
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+            <geometry name="wam_base_collision">
+              <box size="0.001 0.001 0.001" />
+            </geometry>
+            <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+        </collision>
+    </link>
+    <gazebo reference="wam_tool_plate">
+        <material>Gazebo/Grey</material>
+        <selfCollide>true</selfCollide>
+    </gazebo>
+
+    <joint name="wam_tool_plate_joint" type="fixed">
+        <parent link="${parent}"/>
+        <child link="wam_tool_plate"/>
+        <!--origin xyz="-0.045 -0.3 0.0" rpy="${M_PI/2} 0 0" /-->
+        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
+     </joint>
+
+  </xacro:macro>
+
+</robot>