Porto to Jazzy. jazzy
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 16 Dec 2024 01:25:22 +0000 (22:25 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 16 Dec 2024 01:25:22 +0000 (22:25 -0300)
52 files changed:
bhand_bringup/config/bhand_controller.yaml
bhand_bringup/config/joint_state_broadcaster.yaml [new file with mode: 0644]
bhand_bringup/launch/bhand_controller.launch.xml
bhand_bringup/launch/gazebo.launch.xml
bhand_description/CMakeLists.txt
bhand_description/config/ros_gz_bridge.yaml [new file with mode: 0644]
bhand_description/env-hooks/bhand_description.dsv.in [deleted file]
bhand_description/launch/bhand.launch.xml
bhand_description/launch/gazebo.launch.xml
bhand_description/launch/ignition.launch.xml [deleted file]
bhand_description/xacro/bhand.urdf.xacro
bhand_description/xacro/bhand_base.urdf.xacro
bhand_description/xacro/bhand_link1.urdf.xacro
bhand_description/xacro/bhand_link2.urdf.xacro
bhand_description/xacro/bhand_link3.urdf.xacro
bhand_description/xacro/gazebo.urdf.xacro [deleted file]
bhand_description/xacro/gz_ros2_control.urdf.xacro [new file with mode: 0644]
bhand_description/xacro/ros2_control.urdf.xacro
wam_bringup/CMakeLists.txt
wam_bringup/config/computed_torque_controller.yaml
wam_bringup/config/joint_state_broadcaster.yaml [new file with mode: 0644]
wam_bringup/config/pid_independent_joint_controller.yaml
wam_bringup/config/pid_plus_gravity_controller.yaml
wam_bringup/launch/computed_torque_controller.launch.xml
wam_bringup/launch/gazebo.launch.xml
wam_bringup/launch/pid_independent_joint_controller.launch.xml
wam_bringup/launch/pid_plus_gravity_controller.launch.xml
wam_bringup/scripts/set_home.sh [deleted file]
wam_bringup/scripts/step.sh
wam_bringup/scripts/step_home.sh
wam_bringup/scripts/step_zero.sh
wam_description/CMakeLists.txt
wam_description/config/ros_gz_bridge.yaml [new file with mode: 0644]
wam_description/env-hooks/wam_description.dsv.in [deleted file]
wam_description/launch/gazebo.launch.xml
wam_description/launch/ignition.launch.xml [deleted file]
wam_description/launch/wam.launch.xml
wam_description/scripts/set_home.sh [deleted file]
wam_description/scripts/set_zero.sh [deleted file]
wam_description/xacro/gazebo.urdf.xacro [deleted file]
wam_description/xacro/gz_ros2_control.urdf.xacro [new file with mode: 0644]
wam_description/xacro/ros2_control.urdf.xacro
wam_description/xacro/table.urdf.xacro
wam_description/xacro/wam.urdf.xacro
wam_description/xacro/wam_base.urdf.xacro
wam_description/xacro/wam_j1.urdf.xacro
wam_description/xacro/wam_j2.urdf.xacro
wam_description/xacro/wam_j3.urdf.xacro
wam_description/xacro/wam_j4.urdf.xacro
wam_description/xacro/wam_j5.urdf.xacro
wam_description/xacro/wam_j6.urdf.xacro
wam_description/xacro/wam_table.urdf.xacro

index 17f9608..e1af790 100644 (file)
@@ -1,8 +1,9 @@
 bhand_controller:
         ros__parameters:
+                type: position_controllers/JointGroupPositionController
                 joints:
                         - bhand_finger1_joint_2
                         - bhand_finger2_joint_2
                         - bhand_finger3_joint_2
                         - bhand_spread
-
+        
diff --git a/bhand_bringup/config/joint_state_broadcaster.yaml b/bhand_bringup/config/joint_state_broadcaster.yaml
new file mode 100644 (file)
index 0000000..29015ca
--- /dev/null
@@ -0,0 +1,3 @@
+joint_state_broadcaster:
+        ros__parameters:
+                type: joint_state_broadcaster/JointStateBroadcaster
index d76ed96..d317e58 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                           Barrett Hand Bringup
                          Controller Launch File
-          Copyright (C) 2018, 2021 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2018..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
@@ -23,8 +23,8 @@
        <arg name="config" default="$(find-pkg-share bhand_bringup)/config/bhand_controller.yaml"/>
        
        <node name="bhand_controller_spawner" pkg="controller_manager" exec="spawner"
-               args="-t position_controllers/JointGroupPositionController -p $(var config) bhand_controller"/>
+               args="-p $(var config) bhand_controller"/>
 
        <node name="joint_state_broadcaster_spawner" pkg="controller_manager" exec="spawner"
-               args="-t joint_state_broadcaster/JointStateBroadcaster joint_state_broadcaster"/>
+               args="-p $(find-pkg-share bhand_bringup)/config/joint_state_broadcaster.yaml joint_state_broadcaster"/>
 </launch>
index fe89bf5..9326374 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                            Barret Hand Bringup
-                            Gazebo Launch File
-          Copyright (C) 2018..2023 Walter Fetter Lages <w.fetter@ieee.org>
+                          Gazebo Sim Launch File
+          Copyright (C) 2018..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
 *******************************************************************************-->
 
 <launch>
-       <arg name="pause" default="true"/>
+       <arg name="pause" default="false"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
-       <arg name="ignition" default="false"/>
 
        <arg name="controller" default="bhand_controller"/>
        <arg name="config" default="$(find-pkg-share bhand_bringup)/config/$(var controller).yaml"/>
        
-       <include unless="$(var ignition)" file="$(find-pkg-share bhand_description)/launch/gazebo.launch.xml" >
-               <arg name="pause" value="$(var pause)"/>
-               <arg name="gui" value="$(var gui)"/>
-               <arg name="use_sim_time" value="$(var use_sim_time)"/>
-       </include>
-       
-       <include if="$(var ignition)" file="$(find-pkg-share bhand_description)/launch/ignition.launch.xml" >
+       <include file="$(find-pkg-share bhand_description)/launch/gazebo.launch.xml" >
                <arg name="pause" value="$(var pause)"/>
                <arg name="gui" value="$(var gui)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
+               <arg name="world" value="True"/>
        </include>
 
-       <include file="$(find-pkg-share bhand_bringup)/launch/$(var controller).launch.xml" >
+       <include file="$(find-pkg-share bhand_bringup)/launch/$(var controller).launch.xml">
                <arg name="config" value="$(var config)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
        </include>
index 48e9fb6..ff97a71 100644 (file)
@@ -15,8 +15,6 @@ install(DIRECTORY config launch meshes xacro
        DESTINATION share/${PROJECT_NAME}
 )
 
-ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/${PROJECT_NAME}.dsv.in")
-
 if(BUILD_TESTING)
   find_package(ament_lint_auto REQUIRED)
   # the following line skips the linter which checks for copyrights
diff --git a/bhand_description/config/ros_gz_bridge.yaml b/bhand_description/config/ros_gz_bridge.yaml
new file mode 100644 (file)
index 0000000..33167fe
--- /dev/null
@@ -0,0 +1,10 @@
+- ros_topic_name: "/clock"
+  gz_topic_name: "/clock"
+  ros_type_name: "rosgraph_msgs/msg/Clock"
+  gz_type_name: "gz.msgs.Clock"
+#  subscriber_queue: 5       # Default 10
+#  publisher_queue: 6        # Default 10
+#  lazy: true                # Default "false"
+  direction: GZ_TO_ROS      # Default "BIDIRECTIONAL" - Bridge both directions
+                            # "GZ_TO_ROS" - Bridge Ignition topic to ROS
+                            # "ROS_TO_GZ" - Bridge ROS topic to Ignition
diff --git a/bhand_description/env-hooks/bhand_description.dsv.in b/bhand_description/env-hooks/bhand_description.dsv.in
deleted file mode 100644 (file)
index 30a6001..0000000
+++ /dev/null
@@ -1,3 +0,0 @@
-prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
-
-set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
index 91c96aa..631d77d 100644 (file)
@@ -1,10 +1,9 @@
 <launch>
        <arg name="world" default="false"/>
        <arg name="use_sim_time" default="false"/>
-       <arg name="ignition" default="false"/>
 
        <node name="robot_state_publisher" pkg="robot_state_publisher" exec="robot_state_publisher">
-               <param name="robot_description" value="$(command 'xacro $(find-pkg-share bhand_description)/xacro/bhand.urdf.xacro world:=$(var world) ignition:=$(var ignition)')" type="str"/>
+               <param name="robot_description" value="$(command 'xacro $(find-pkg-share bhand_description)/xacro/bhand.urdf.xacro world:=$(var world)')" type="str"/>
                <param name="use_sim_time" value="$(var use_sim_time)"/>
        </node>
 </launch>
index de382c1..280f8e0 100644 (file)
@@ -1,21 +1,50 @@
+<!--******************************************************************************
+                           Bhand  Description
+                        Gazebo Sim Launch File
+          Copyright (C) 2022, 2024 Walter Fetter Lages <w.fetter@ieee.org>
+
+        This program is free software: you can redistribute it and/or modify
+        it under the terms of the GNU General Public License as published by
+        the Free Software Foundation, either version 3 of the License, or
+        (at your option) any later version.
+
+        This program is distributed in the hope that it will be useful, but
+        WITHOUT ANY WARRANTY; without even the implied warranty of
+        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+        Geneal Public License for more details.
+
+        You should have received a copy of the GNU General Public License
+        along with this program.  If not, see
+        <http://www.gnu.org/licenses/>.
+
+*******************************************************************************-->
+
 <launch>
-       <arg name="pause" default="true"/>
+       <arg name="pause" default="false"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
        <arg name="world" default="true"/>
 
-       <group> <include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
-               <arg name="pause" value="$(var pause)"/>
-               <arg name="gui" value="$(var gui)"/>
+       <arg unless="$(var pause)" name="gz_pause" default="-r"/>
+       <arg if="$(var pause)" name="gz_pause" default=""/>
+       
+       <arg unless="$(var gui)" name="gz_gui" default="-s"/>
+       <arg if="$(var gui)" name="gz_gui" default=""/>
+
+       <include file="$(find-pkg-share ros_gz_sim)/launch/gz_sim.launch.py">
+               <arg name="gz_args" value="$(var gz_pause) $(var gz_gui) empty.sdf"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
-               <arg name="world" value="worlds/empty_sky.world" />
-               <arg name="extra_gazebo_args" value="--ros-args --params-file $(find-pkg-share bhand_description)/config/gazebo.yaml"/>
-       </include> </group>
+       </include>
        
        <include file="$(find-pkg-share bhand_description)/launch/bhand.launch.xml">
                <arg name="world" value="$(var world)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
        </include>
 
-       <node name="bhand_spawner" pkg="gazebo_ros" exec="spawn_entity.py" args="-topic robot_description -entity bhand"/>
+       <node name="bhand_spawner" pkg="ros_gz_sim" exec="create" args="-topic robot_description -name bhand"/>
+
+       <node name="ros_gz_bridge" pkg="ros_gz_bridge" exec="parameter_bridge">
+               <param name="config_file" value="$(find-pkg-share bhand_description)/config/ros_gz_bridge.yaml"/>>
+               <param name="use_sim_time" value="$(var use_sim_time)"/>
+       </node>
 </launch>
diff --git a/bhand_description/launch/ignition.launch.xml b/bhand_description/launch/ignition.launch.xml
deleted file mode 100644 (file)
index 3621bd1..0000000
+++ /dev/null
@@ -1,49 +0,0 @@
-<!--******************************************************************************
-                           Bhand  Description
-                        Gazebo Ignition Launch File
-          Copyright (C) 2022, 2023 Walter Fetter Lages <w.fetter@ieee.org>
-
-        This program is free software: you can redistribute it and/or modify
-        it under the terms of the GNU General Public License as published by
-        the Free Software Foundation, either version 3 of the License, or
-        (at your option) any later version.
-
-        This program is distributed in the hope that it will be useful, but
-        WITHOUT ANY WARRANTY; without even the implied warranty of
-        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-        Geneal Public License for more details.
-
-        You should have received a copy of the GNU General Public License
-        along with this program.  If not, see
-        <http://www.gnu.org/licenses/>.
-
-*******************************************************************************-->
-
-<launch>
-       <arg name="pause" default="true"/>
-       <arg name="gui" default="true"/>
-       <arg name="use_sim_time" default="true"/>
-       <arg name="world" default="true"/>
-
-       <arg unless="$(var pause)" name="gz_pause" default="-r"/>
-       <arg if="$(var pause)" name="gz_pause" default=""/>
-       
-       <arg unless="$(var gui)" name="gz_gui" default="-s"/>
-       <arg if="$(var gui)" name="gz_gui" default=""/>
-
-       <include file="$(find-pkg-share ros_gz_sim)/launch/gz_sim.launch.py">
-               <arg name="gz_args" value="$(var gz_pause) $(var gz_gui) empty.sdf"/>
-       </include>
-       
-       <include file="$(find-pkg-share bhand_description)/launch/bhand.launch.xml">
-               <arg name="world" value="$(var world)"/>
-               <arg name="use_sim_time" value="$(var use_sim_time)"/>
-               <arg name="ignition" value="true"/>
-       </include>
-
-       <node name="bhand_spawner" pkg="ros_gz_sim" exec="create" args="-topic robot_description -name bhand"/>
-
-       <node name="clock_bridge" pkg="ros_gz_bridge" exec="parameter_bridge" args="/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock">
-               <param name="use_sim_time" value="$(var use_sim_time)"/>
-       </node>
-</launch>
index 5b40b37..6cf0128 100644 (file)
@@ -1,10 +1,7 @@
 <?xml version="1.0"?>
 <robot name="bhand" xmlns:xacro="http://www.ros.org/wiki/xacro">
   <xacro:arg name="world" default="false"/>
-  <xacro:arg name="ignition" default="false"/>
 
-  <xacro:property name="M_PI" value="3.1415926535897931"/>
-  
   <xacro:include filename="$(find bhand_description)/xacro/bhand_base.urdf.xacro"/>
   <xacro:include filename="$(find bhand_description)/xacro/bhand_link1.urdf.xacro"/>
   <xacro:include filename="$(find bhand_description)/xacro/bhand_link2.urdf.xacro"/>
        Finger spread frame
 -->
                                <mass value="0.14109"/>
-                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>
                                <!--inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/-->
                                <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
                        </inertial>
                </inertial_attr>
-               <origin xyz="-0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0.0 0.0"/> 
-               <limit effort="30.0" velocity="1.5" lower="0" upper="${M_PI}"/>
+               <origin xyz="-0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0.0 0.0"/>
+               <limit effort="30.0" velocity="1.5" lower="0" upper="${pi}"/>
                <mimic_attr/>
   </xacro:bhand_link1>
 
        Finger spread frame
 -->
                                <mass value="0.14109"/>
-                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>
                                <!--inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/-->
                                <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
                        </inertial>
                </inertial_attr>                 
-               <origin xyz="0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0.0 0.0"/> 
-               <limit effort="30" velocity="1.5" lower="-${M_PI}" upper="0"/>
+               <origin xyz="0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0.0 0.0"/>
+               <limit effort="30" velocity="1.5" lower="-${pi}" upper="0"/>
                <mimic_attr>
                        <mimic joint="bhand_spread" multiplier="-1.0" offset="0.0"/>
                </mimic_attr>
        Is this included in base? Fix this...
 -->
                                <mass value="0.14109"/>
-                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>
                                <!--inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/-->
                                <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
 
                        </inertial>
                </inertial_attr>
                <!--inertial_attr/-->
-               <origin xyz="0.0 0.0 ${0.1325-0.06}" rpy="0.0 0.0 ${M_PI}"/> 
+               <origin xyz="0.0 0.0 ${0.1325-0.06}" rpy="0.0 0.0 ${pi}"/>
                <limit effort="0.0" velocity="0.0" lower="0.0" upper="0.0"/>
                <mimic_attr/>
   </xacro:bhand_link1>
   <xacro:include filename="ros2_control.urdf.xacro"/>
   
   <xacro:if value="$(arg world)">
-       <xacro:include filename="gazebo.urdf.xacro"/>
+       <xacro:include filename="gz_ros2_control.urdf.xacro"/>
   </xacro:if>
 
 </robot>
index fd31c23..d084aa1 100644 (file)
@@ -1,8 +1,6 @@
 <?xml version="1.0" ?>
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
-
-   <xacro:property name="M_PI" value="3.1415926535897931" />
    
    <xacro:macro name="bhand_base" params="parent link joint">
 
@@ -18,7 +16,7 @@
                        <inertia ixx="0.00067154" ixy="2.9365e-7" ixz="-7.6321e-7" iyy="0.00048844" iyz="-7.1984e-5" izz="0.00060401"/>
                </inertial>
                <visual>
-                       <origin rpy="0 0 ${-M_PI/2}" xyz="0 0 -0.06"/>
+                       <origin rpy="0 0 ${-pi/2}" xyz="0 0 -0.06"/>
                        <geometry>
                                <mesh filename="package://bhand_description/meshes/bh_base.stl" />
                        </geometry>
@@ -27,7 +25,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="0 0 ${-M_PI/2}" xyz="0 0 -0.06"/>
+                       <origin rpy="0 0 ${-pi/2}" xyz="0 0 -0.06"/>
                        <geometry>
                                <mesh filename="package://bhand_description/meshes/bh_base.stl" />
                        </geometry>
index 76d0a7d..67f3b8b 100644 (file)
@@ -7,7 +7,7 @@
        <link name="bhand_${link}">
                <xacro:insert_block name="inertial_attr"/>
                <visual>
-                       <origin rpy="0 0 ${M_PI/2}" xyz="0 0 0"/>
+                       <origin rpy="0 0 ${pi/2}" xyz="0 0 0"/>
                        <geometry>
                                <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
                        </geometry>
@@ -16,7 +16,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="0 0 ${M_PI/2}" xyz="0 0 0"/>
+                       <origin rpy="0 0 ${pi/2}" xyz="0 0 0"/>
                        <geometry>
                                <mesh filename="package://bhand_description/meshes/bh_link1.stl" />
                        </geometry>
index f0dea95..63e4c8d 100644 (file)
                <!--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" /--> 
 
-               <origin xyz="0.0 0.05 0.0" rpy="${M_PI/2} 0.0 ${M_PI/2}" />
+               <origin xyz="0.0 0.05 0.0" rpy="${pi/2} 0.0 ${pi/2}" />
                <parent link="bhand_${parent}"/>
                <child link="bhand_${link}" />
                <axis xyz="0 0 1"/>
-               <limit effort="30" velocity="1.5" lower="0.0" upper="${140 * M_PI / 180}" />
+               <limit effort="30" velocity="1.5" lower="0.0" upper="${140 * pi / 180}" />
 
                <dynamics damping="10" friction="1"/>
 
index d81cdd2..2fe68a0 100644 (file)
        <joint name="bhand_${joint}" type="revolute">
                <!--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" /--> 
-               <!--origin xyz="0.070 0 0" rpy="0 0 ${42 * M_PI / 180}" /-->
+               <!--origin xyz="0.070 0 0" rpy="0 0 ${42 * pi / 180}" /-->
 
-               <origin xyz="0.070 0.0 0.0" rpy="0.0 0.0 ${40 * M_PI / 180}" /> 
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0.0 ${40 * pi / 180}" /> 
                <parent link="bhand_${parent}"/>
                <child link="bhand_${link}" />
                <axis xyz="0 0 1"/>
                
-               <!--limit lower="0" upper="${48 * M_PI / 180}" effort="30" velocity="2.0"/-->
-               <limit effort="30" velocity="1.5" lower="0" upper="${2.44346095 - 40 * M_PI / 180}" />
+               <!--limit lower="0" upper="${48 * pi / 180}" effort="30" velocity="2.0"/-->
+               <limit effort="30" velocity="1.5" lower="0" upper="${2.44346095 - 40 * pi / 180}" />
 
                <dynamics damping="10" friction="1"/>
 
diff --git a/bhand_description/xacro/gazebo.urdf.xacro b/bhand_description/xacro/gazebo.urdf.xacro
deleted file mode 100644 (file)
index 8696a29..0000000
+++ /dev/null
@@ -1,27 +0,0 @@
-<?xml version="1.0"?>
-<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
-
-       <xacro:arg name="ignition" default="false"/>
-       
-       <!-- Gazebo Classic -->
-       <xacro:unless value="$(arg ignition)">
-               <gazebo>
-                       <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
-                               <robot_param>robot_description</robot_param>
-                               <robot_param_node>robot_state_publisher</robot_param_node>
-                               <parameters>$(find bhand_description)/config/controller_manager.yaml</parameters>
-                       </plugin>
-               </gazebo>
-       </xacro:unless>
-       
-       <!-- Gazebo Ignition -->
-       <xacro:if value="$(arg ignition)">
-               <gazebo>
-                       <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
-                               <robot_param>robot_description</robot_param>
-                               <robot_param_node>robot_state_publisher</robot_param_node>
-                               <parameters>$(find bhand_description)/config/controller_manager.yaml</parameters>
-                       </plugin>
-               </gazebo>
-       </xacro:if>
-</robot>
diff --git a/bhand_description/xacro/gz_ros2_control.urdf.xacro b/bhand_description/xacro/gz_ros2_control.urdf.xacro
new file mode 100644 (file)
index 0000000..9457b51
--- /dev/null
@@ -0,0 +1,9 @@
+<?xml version="1.0"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <gazebo>
+               <plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
+                       <parameters>$(find bhand_description)/config/controller_manager.yaml</parameters>
+               </plugin>
+       </gazebo>
+</robot>
index a1b52cc..5d4fa71 100644 (file)
@@ -2,76 +2,71 @@
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
        <ros2_control name="BhandSystem" type="system">
-               <!-- Gazebo Classic -->
-               <xacro:unless value="$(arg ignition)">
-                       <hardware>
-                               <plugin>gazebo_ros2_control/GazeboSystem</plugin>
-                       </hardware>
-       </xacro:unless>
-       <xacro:if value="$(arg ignition)">
-                <!-- Gazebo Ignition -->
                <hardware>
-                       <plugin>ign_ros2_control/IgnitionSystem</plugin>
+                       <plugin>gz_ros2_control/GazeboSimSystem</plugin>
                </hardware>
-       </xacro:if>
 
                <joint name="bhand_finger1_joint_2">
                        <command_interface name="position">
                                <param name="min">0.0</param>
-                               <param name="max">${140 * M_PI /180}</param>
+                               <param name="max">${140 * pi /180}</param>
                        </command_interface>
-                       <state_interface name="position"/>
+                       <state_interface name="position">
+                               <param name="initial_value">${140 * pi /180}</param>
+                       </state_interface>
                </joint>
                
                <joint name="bhand_finger1_joint_3">
                        <param name="mimic">bhand_finger1_joint_2</param>
                        <param name="multiplier">${48 / 140}</param>
-                       <command_interface name="position"/>
                        <state_interface name="position"/>
                </joint>
                
                <joint name="bhand_finger2_joint_2">
                        <command_interface name="position">
-                               <param name="min">0,9</param>
-                               <param name="max">${140 * M_PI /180}</param>
+                               <param name="min">0.0</param>
+                               <param name="max">${140 * pi /180}</param>
                        </command_interface>
-                       <state_interface name="position"/>
+                       <state_interface name="position">
+                               <param name="initial_value">${140 * pi /180}</param>
+                       </state_interface>
                </joint>
                
                <joint name="bhand_finger2_joint_3">
                        <param name="mimic">bhand_finger2_joint_2</param>
                        <param name="multiplier">${48 / 140}</param>
-                       <command_interface name="position"/>
                        <state_interface name="position"/>
                </joint>
 
                <joint name="bhand_finger3_joint_2">
                        <command_interface name="position">
                                <param name="min">0.0</param>
-                               <param name="max">${140 * M_PI /180}</param>
+                               <param name="max">${140 * pi /180}</param>
                        </command_interface>
-                       <state_interface name="position"/>
+                       <state_interface name="position">
+                               <param name="initial_value">${140 * pi /180}</param>
+                       </state_interface>
                </joint>
 
                <joint name="bhand_finger3_joint_3">
                        <param name="mimic">bhand_finger3_joint_2</param>
                        <param name="multiplier">${48 / 140}</param>
-                       <command_interface name="position"/>
                        <state_interface name="position"/>
                </joint>
                
                <joint name="bhand_spread">
                        <command_interface name="position">
                                <param name="min">0.0</param>
-                               <param name="max">${M_PI}</param>
+                               <param name="max">${pi}</param>
                        </command_interface>
-                       <state_interface name="position"/>
+                       <state_interface name="position">
+                               <param name="initial_value">${pi}</param>
+                       </state_interface>
                </joint>
                
                <joint name="bhand_spread_mimic">
                        <param name="mimic">bhand_spread</param>
                        <param name="multiplier">-1.0</param>
-                       <command_interface name="position"/>
                        <state_interface name="position"/>
                </joint>
        </ros2_control>
index 607ac0a..61b3450 100644 (file)
@@ -16,7 +16,6 @@ install(DIRECTORY config launch
 )
 
 install(PROGRAMS
-       scripts/set_home.sh
        scripts/step.sh
        scripts/step_home.sh
        scripts/step_zero.sh
index 422fbb3..849a413 100644 (file)
@@ -1,5 +1,6 @@
 computed_torque_controller:
         ros__parameters:
+                type: effort_controllers/ComputedTorqueController
                 joints:
                         - wam_joint_1
                         - wam_joint_2
diff --git a/wam_bringup/config/joint_state_broadcaster.yaml b/wam_bringup/config/joint_state_broadcaster.yaml
new file mode 100644 (file)
index 0000000..29015ca
--- /dev/null
@@ -0,0 +1,3 @@
+joint_state_broadcaster:
+        ros__parameters:
+                type: joint_state_broadcaster/JointStateBroadcaster
index f143aab..9d8e010 100644 (file)
@@ -1,6 +1,7 @@
 pid_independent_joint_controller:
         ros__parameters:
-                joints:
+                type: pid_controller/PidController
+                dof_names:
                         - wam_joint_1
                         - wam_joint_2
                         - wam_joint_3
@@ -8,11 +9,14 @@ pid_independent_joint_controller:
                         - wam_joint_5
                         - wam_joint_6
                         - wam_joint_7
+                command_interface: effort
+                reference_and_state_interfaces: ["position"]
+                gains:
                 # PID parameters from /etc/barrett/wam7w.conf
-                wam_joint_1/pid: {p: 900.0, i: 2.5, d: 10.0, i_clamp_min: -25.0, i_clamp_max: 25.0}
-                wam_joint_2/pid: {p: 2500.0, i: 5.0, d: 20.0, i_clamp_min: -20.0, i_clamp_max: 20.0}
-                wam_joint_3/pid: {p: 600.0, i: 2.0, d: 5.0, i_clamp_min: -15.0, i_clamp_max: 15.0}
-                wam_joint_4/pid: {p: 500.0, i: 0.5, d: 2.0, i_clamp_min: -15.0, i_clamp_max: 15.0}
-                wam_joint_5/pid: {p: 50.0, i: 0.5, d: 0.5, i_clamp_min: -5.0, i_clamp_max: 5.0}
-                wam_joint_6/pid: {p: 50.0, i: 0.5, d: 0.5, i_clamp_min: -5.0, i_clamp_max: 5.0}
-                wam_joint_7/pid: {p: 8.0, i: 0.1, d: 0.05, i_clamp_min: -5.0, i_clamp_max: 5.0}
+                        wam_joint_1: {p: 900.0, i: 2.5, d: 10.0, i_clamp_min: -25.0, i_clamp_max: 25.0, antiwindup: false}
+                        wam_joint_2: {p: 2500.0, i: 5.0, d: 20.0, i_clamp_min: -20.0, i_clamp_max: 20.0, antiwindup: false}
+                        wam_joint_3: {p: 600.0, i: 2.0, d: 5.0, i_clamp_min: -15.0, i_clamp_max: 15.0, antiwindup: false}
+                        wam_joint_4: {p: 500.0, i: 0.5, d: 2.0, i_clamp_min: -15.0, i_clamp_max: 15.0, antiwindup: false}
+                        wam_joint_5: {p: 50.0, i: 0.5, d: 0.5, i_clamp_min: -5.0, i_clamp_max: 5.0, antiwindup: false}
+                        wam_joint_6: {p: 50.0, i: 0.5, d: 0.5, i_clamp_min: -5.0, i_clamp_max: 5.0, antiwindup: false}
+                        wam_joint_7: {p: 8.0, i: 0.1, d: 0.05, i_clamp_min: -5.0, i_clamp_max: 5.0, antiwindup: false}
index bad0c11..5ceafd5 100644 (file)
@@ -1,5 +1,6 @@
 pid_plus_gravity_controller:
         ros__parameters:
+                type: effort_controllers/PidPlusGravityController
                 joints:
                         - wam_joint_1
                         - wam_joint_2
index 90b1d1c..415888e 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                            Barrett WAM Bringup
                    Computed Torque  Controller Launch File
-          Copyright (C) 2021 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2021..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
@@ -23,8 +23,8 @@
        <arg name="config" default="$(find-pkg-share wam_bringup)/config/computed_torque_controller.yaml"/>
        
        <node name="computed_torque_controller_spawner" pkg="controller_manager" exec="spawner"
-               args="-t effort_controllers/ComputedTorqueController -p $(var config) --controller-manager-timeout 10 computed_torque_controller"/>
+               args="-p $(var config) computed_torque_controller"/>
                
        <node name="joint_state_broadcaster_spawner" pkg="controller_manager" exec="spawner"
-               args="-t joint_state_broadcaster/JointStateBroadcaster --controller-manager-timeout 10 joint_state_broadcaster"/>
+               args="-p $(find-pkg-share wam_bringup)/config/joint_state_broadcaster.yaml joint_state_broadcaster"/>
 </launch>
index 454d592..1c27baa 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                             Barrett WAM Bringup
-                            Gazebo Launch File
-          Copyright (C) 2018..2023 Walter Fetter Lages <w.fetter@ieee.org>
+                           Gazebo Sim Launch File
+          Copyright (C) 2018..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
 *******************************************************************************-->
 
 <launch>
-       <arg name="pause" default="true"/>
+       <arg name="pause" default="false"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
        <arg name="table" default="true"/>
        <arg name="bhand" default="true"/>
-       <arg name="ignition" default="false"/>
 
        <!-- This is the default Barrett WAM Controller, used by libbarrett -->
        <arg name="controller" default="pid_plus_gravity_controller"/>
        <arg name="config" default="$(find-pkg-share wam_bringup)/config/$(var controller).yaml"/>
        
-       <include unless="$(var ignition)" file="$(find-pkg-share wam_description)/launch/gazebo.launch.xml" >
-               <arg name="pause" value="$(var pause)"/>
-               <arg name="gui" value="$(var gui)"/>
-               <arg name="use_sim_time" value="$(var use_sim_time)"/>
-               <arg name="table" value="$(var table)"/>
-               <arg name="bhand" value="$(var bhand)"/>
-       </include>
-       
-       <include if="$(var ignition)" file="$(find-pkg-share wam_description)/launch/ignition.launch.xml" >
+       <include file="$(find-pkg-share wam_description)/launch/gazebo.launch.xml" >
                <arg name="pause" value="$(var pause)"/>
                <arg name="gui" value="$(var gui)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
@@ -56,6 +47,6 @@
                <arg name="bhand_config" default="$(find-pkg-share bhand_bringup)/config/bhand_controller.yaml"/>
        
                <node name="bhand_controller_spawner" pkg="controller_manager" exec="spawner"
-                       args="-t position_controllers/JointGroupPositionController -p $(var bhand_config) bhand_controller"/>
+                       args="-p $(var bhand_config) bhand_controller"/>
        </group>
 </launch>
index 1cef4ee..52e7dcf 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                           Barrett WAM Bringup
                          PID Controller Launch File
-          Copyright (C) 2018, 2021 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2018..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
        <arg name="config" default="$(find-pkg-share wam_bringup)/config/pid_independent_joint_controller.yaml"/>
        
        <node name="pid_independent_joint_controller_spawner" pkg="controller_manager" exec="spawner"
-               args="-t effort_controllers/JointGroupPositionController -p $(var config) --controller-manager-timeout 10 group_controller"/>
+               args="-p $(var config) pid_independent_joint_controller"/>
                
        <node name="joint_state_broadcaster_spawner" pkg="controller_manager" exec="spawner"
-               args="-t joint_state_broadcaster/JointStateBroadcaster --controller-manager-timeout 10 joint_state_broadcaster"/>
+               args="-p $(find-pkg-share wam_bringup)/config/joint_state_broadcaster.yaml joint_state_broadcaster"/>
+
+       <executable cmd="ros2 topic pub /pid_independent_joint_controller/reference control_msgs/msg/MultiDOFCommand
+               '{dof_names: [\'wam_joint_1\', \'wam_joint_2\', \'wam_joint_3\', \'wam_joint_4\', \'wam_joint_5\', \'wam_joint_6\', \'wam_joint_7\'], 
+               values: [0.0, -2.0, 0.0, 3.1, 0.0, 0.0, 0.0]}' -1" output="screen"/>
 </launch>
index 2865d65..10f4504 100644 (file)
@@ -1,7 +1,7 @@
 <!--******************************************************************************
                           Barrett WAM Bringup
                      PID+gravity Controller Launch File
-          Copyright (C) 2021 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2021..2024 Walter Fetter Lages <w.fetter@ieee.org>
 
         This program is free software: you can redistribute it and/or modify
         it under the terms of the GNU General Public License as published by
@@ -23,8 +23,8 @@
        <arg name="config" default="$(find-pkg-share wam_bringup)/config/pid_plus_gravity_controller.yaml"/>
        
        <node name="pid_plus_gravity_controller_spawner" pkg="controller_manager" exec="spawner"
-               args="-t effort_controllers/PidPlusGravityController -p $(var config) --controller-manager-timeout 10 pid_plus_gravity_controller"/>
+               args="-p $(var config) pid_plus_gravity_controller"/>
                
        <node name="joint_state_broadcaster_spawner" pkg="controller_manager" exec="spawner"
-               args="-t joint_state_broadcaster/JointStateBroadcaster --controller-manager-timeout 10 joint_state_broadcaster"/>
+               args="-p $(find-pkg-share wam_bringup)/config/joint_state_broadcaster.yaml joint_state_broadcaster"/>
 </launch>
diff --git a/wam_bringup/scripts/set_home.sh b/wam_bringup/scripts/set_home.sh
deleted file mode 100755 (executable)
index 710d3ef..0000000
+++ /dev/null
@@ -1,13 +0,0 @@
-#!/bin/bash
-
-ros2 service 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, -2.0, 0.0, 3.1, 0.0, 0.0, 0.0]"
-
-ros2 topic pub /command \
-trajectory_msgs/msg/JointTrajectoryPoint \
-"{positions: [0.0, -2.0, 0.0, 3.1, 0.0, 0.0, 0.0], \
-velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
-accelerations: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],  \
-effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
-time_from_start: {sec: 0, nanosec: 0}}" "-1"
index 2690bee..b3ceb69 100755 (executable)
@@ -4,10 +4,23 @@ if [ "$#" -ne 7 ]; then
        echo "Error: There should be 7 parameters."
        exit -1;
 fi;
-ros2 topic pub /command \
+
+TOPICLIST=`ros2 topic list`
+       
+if echo $TOPICLIST | grep -qw "/command" ; then
+       ros2 topic pub /command \
 trajectory_msgs/msg/JointTrajectoryPoint \
 "{positions: [$1, $2, $3, $4, $5, $6, $7], \
 velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 accelerations: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],  \
 effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 time_from_start: {sec: 0, nanosec: 0}}" "-1"
+
+elif echo $TOPICLIST | grep -qw "/pid_independent_joint_controller/reference" ; then
+       ros2 topic pub /pid_independent_joint_controller/reference \
+control_msgs/msg/MultiDOFCommand \
+"{dof_names: [\"wam_joint_1\", \"wam_joint_2\", \"wam_joint_3\", \"wam_joint_4\", \"wam_joint_5\", \"wam_joint_6\", \"wam_joint_7\"], values: [$1, $2, $3, $4, $5, $6, $7]}" "-1"
+
+else
+       echo Unkown controller
+fi
index c999a38..3c18760 100755 (executable)
@@ -1,9 +1,21 @@
 #!/bin/bash
 
-ros2 topic pub /command \
+TOPICLIST=`ros2 topic list`
+       
+if echo $TOPICLIST | grep -qw "/command" ; then
+       ros2 topic pub /command \
 trajectory_msgs/msg/JointTrajectoryPoint \
 "{positions: [0.0, -2.0, 0.0, 3.1, 0.0, 0.0, 0.0], \
 velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 accelerations: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],  \
 effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 time_from_start: {sec: 0, nanosec: 0}}" "-1"
+
+elif echo $TOPICLIST | grep -qw "/pid_independent_joint_controller/reference" ; then
+       ros2 topic pub /pid_independent_joint_controller/reference \
+control_msgs/msg/MultiDOFCommand \
+"{dof_names: [\"wam_joint_1\", \"wam_joint_2\", \"wam_joint_3\", \"wam_joint_4\", \"wam_joint_5\", \"wam_joint_6\", \"wam_joint_7\"], values: [0.0, -2.0, 0.0, 3.1, 0.0, 0.0, 0.0]}" "-1"
+
+else
+       echo Unkown controller
+fi
index f8d3648..bfabfbd 100755 (executable)
@@ -1,9 +1,21 @@
 #!/bin/bash
 
-ros2 topic pub /command \
+TOPICLIST=`ros2 topic list`
+
+if echo $TOPICLIST | grep -qw "/command" ; then
+       ros2 topic pub /command \
 trajectory_msgs/msg/JointTrajectoryPoint \
 "{positions: [0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0], \
 velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 accelerations: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],  \
 effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], \
 time_from_start: {sec: 0, nanosec: 0}}" "-1"
+
+elif echo $TOPICLIST | grep -qw "/pid_independent_joint_controller/reference" ; then
+       ros2 topic pub /pid_independent_joint_controller/reference \
+control_msgs/msg/MultiDOFCommand \
+"{dof_names: [\"wam_joint_1\", \"wam_joint_2\", \"wam_joint_3\", \"wam_joint_4\", \"wam_joint_5\", \"wam_joint_6\", \"wam_joint_7\"], values: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}" "-1"
+
+else
+       echo Unkown controller
+fi
index f307024..b321cc6 100644 (file)
@@ -15,12 +15,6 @@ install(DIRECTORY config launch meshes xacro
        DESTINATION share/${PROJECT_NAME}
 )
 
-install(PROGRAMS scripts/set_home.sh scripts/set_zero.sh
-       DESTINATION lib/${PROJECT_NAME}
-)
-
-ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/${PROJECT_NAME}.dsv.in")
-
 if(BUILD_TESTING)
   find_package(ament_lint_auto REQUIRED)
   # the following line skips the linter which checks for copyrights
diff --git a/wam_description/config/ros_gz_bridge.yaml b/wam_description/config/ros_gz_bridge.yaml
new file mode 100644 (file)
index 0000000..33167fe
--- /dev/null
@@ -0,0 +1,10 @@
+- ros_topic_name: "/clock"
+  gz_topic_name: "/clock"
+  ros_type_name: "rosgraph_msgs/msg/Clock"
+  gz_type_name: "gz.msgs.Clock"
+#  subscriber_queue: 5       # Default 10
+#  publisher_queue: 6        # Default 10
+#  lazy: true                # Default "false"
+  direction: GZ_TO_ROS      # Default "BIDIRECTIONAL" - Bridge both directions
+                            # "GZ_TO_ROS" - Bridge Ignition topic to ROS
+                            # "ROS_TO_GZ" - Bridge ROS topic to Ignition
diff --git a/wam_description/env-hooks/wam_description.dsv.in b/wam_description/env-hooks/wam_description.dsv.in
deleted file mode 100644 (file)
index 30a6001..0000000
+++ /dev/null
@@ -1,3 +0,0 @@
-prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
-
-set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
index 261ca30..0a043c3 100644 (file)
@@ -1,17 +1,41 @@
+<!--******************************************************************************
+                         Barrett WAM  Description
+                         Gazebo Sim Launch File
+          Copyright (C) 2022, 2024 Walter Fetter Lages <w.fetter@ieee.org>
+
+        This program is free software: you can redistribute it and/or modify
+        it under the terms of the GNU General Public License as published by
+        the Free Software Foundation, either version 3 of the License, or
+        (at your option) any later version.
+
+        This program is distributed in the hope that it will be useful, but
+        WITHOUT ANY WARRANTY; without even the implied warranty of
+        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+        Geneal Public License for more details.
+
+        You should have received a copy of the GNU General Public License
+        along with this program.  If not, see
+        <http://www.gnu.org/licenses/>.
+
+*******************************************************************************-->
+
 <launch>
-       <arg name="pause" default="true"/>
+       <arg name="pause" default="false"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
        <arg name="table" default="true"/>
        <arg name="bhand" default="true"/>
 
-       <group> <include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
-               <arg name="pause" value="$(var pause)"/>
-               <arg name="gui" value="$(var gui)"/>
+       <arg unless="$(var pause)" name="gz_pause" default="-r"/>
+       <arg if="$(var pause)" name="gz_pause" default=""/>
+       
+       <arg unless="$(var gui)" name="gz_gui" default="-s"/>
+       <arg if="$(var gui)" name="gz_gui" default=""/>
+
+       <include file="$(find-pkg-share ros_gz_sim)/launch/gz_sim.launch.py">
+               <arg name="gz_args" value="$(var gz_pause) $(var gz_gui) empty.sdf"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
-               <arg name="world" value="worlds/empty_sky.world"/>
-               <arg name="extra_gazebo_args" value="--ros-args --params-file $(find-pkg-share wam_description)/config/gazebo.yaml"/>
-       </include> </group>
+       </include>
        
        <include file="$(find-pkg-share wam_description)/launch/wam.launch.xml">
                <arg name="table" value="$(var table)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
        </include>
 
-       <node name="wam_spawner" pkg="gazebo_ros" exec="spawn_entity.py" args="-topic robot_description -entity wam"/>
+       <node name="wam_spawner" pkg="ros_gz_sim" exec="create" args="-topic robot_description -name wam"/>
+
+       <node name="ros_gz_bridge" pkg="ros_gz_bridge" exec="parameter_bridge">
+               <param name="config_file" value="$(find-pkg-share wam_description)/config/ros_gz_bridge.yaml"/>>
+               <param name="use_sim_time" value="$(var use_sim_time)"/>
+       </node>
 </launch>
diff --git a/wam_description/launch/ignition.launch.xml b/wam_description/launch/ignition.launch.xml
deleted file mode 100644 (file)
index a59e2b9..0000000
+++ /dev/null
@@ -1,51 +0,0 @@
-<!--******************************************************************************
-                         Barrett WAM  Description
-                         Gazebo Ignitio Launch File
-          Copyright (C) 2022, 2023 Walter Fetter Lages <w.fetter@ieee.org>
-
-        This program is free software: you can redistribute it and/or modify
-        it under the terms of the GNU General Public License as published by
-        the Free Software Foundation, either version 3 of the License, or
-        (at your option) any later version.
-
-        This program is distributed in the hope that it will be useful, but
-        WITHOUT ANY WARRANTY; without even the implied warranty of
-        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-        Geneal Public License for more details.
-
-        You should have received a copy of the GNU General Public License
-        along with this program.  If not, see
-        <http://www.gnu.org/licenses/>.
-
-*******************************************************************************-->
-
-<launch>
-       <arg name="pause" default="true"/>
-       <arg name="gui" default="true"/>
-       <arg name="use_sim_time" default="true"/>
-       <arg name="table" default="true"/>
-       <arg name="bhand" default="true"/>
-
-       <arg unless="$(var pause)" name="gz_pause" default="-r"/>
-       <arg if="$(var pause)" name="gz_pause" default=""/>
-       
-       <arg unless="$(var gui)" name="gz_gui" default="-s"/>
-       <arg if="$(var gui)" name="gz_gui" default=""/>
-
-       <include file="$(find-pkg-share ros_gz_sim)/launch/gz_sim.launch.py">
-               <arg name="gz_args" value="$(var gz_pause) $(var gz_gui) empty.sdf"/>
-       </include>
-       
-       <include file="$(find-pkg-share wam_description)/launch/wam.launch.xml">
-               <arg name="table" value="$(var table)"/>
-               <arg name="bhand" value="$(var bhand)"/>
-               <arg name="use_sim_time" value="$(var use_sim_time)"/>
-               <arg name="ignition" value="true"/>
-       </include>
-
-       <node name="wam_spawner" pkg="ros_ign_gazebo" exec="create" args="-topic robot_description -name wam"/>
-
-       <node name="clock_bridge" pkg="ros_gz_bridge" exec="parameter_bridge" args="/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock">
-               <param name="use_sim_time" value="$(var use_sim_time)"/>
-       </node>
-</launch>
index 7d1bb12..7524fa6 100644 (file)
@@ -3,10 +3,9 @@
        <arg name="bhand" default="true"/>
        <arg name="world" default="false"/>
        <arg name="use_sim_time" default="false"/>
-       <arg name="ignition" default="false"/>
 
        <node name="robot_state_publisher" pkg="robot_state_publisher" exec="robot_state_publisher">
-               <param name="robot_description" value="$(command 'xacro $(find-pkg-share wam_description)/xacro/wam.urdf.xacro world:=$(var world) table:=$(var table) bhand:=$(var bhand) ignition:=$(var ignition)')" type="str"/>
+               <param name="robot_description" value="$(command 'xacro $(find-pkg-share wam_description)/xacro/wam.urdf.xacro world:=$(var world) table:=$(var table) bhand:=$(var bhand)')" type="str"/>
                <param name="use_sim_time" value="$(var use_sim_time)"/>
        </node>
 </launch>
diff --git a/wam_description/scripts/set_home.sh b/wam_description/scripts/set_home.sh
deleted file mode 100755 (executable)
index d14b55d..0000000
+++ /dev/null
@@ -1,6 +0,0 @@
-#!/bin/bash
-
-ros2 service 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,-2.0,0.0,3.1,0.0,0.0,0.0]"
diff --git a/wam_description/scripts/set_zero.sh b/wam_description/scripts/set_zero.sh
deleted file mode 100755 (executable)
index 7c9cb59..0000000
+++ /dev/null
@@ -1,6 +0,0 @@
-#!/bin/bash
-
-ros2 service 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.0,0.0,0.0,0.0,0.0,0.0]"
diff --git a/wam_description/xacro/gazebo.urdf.xacro b/wam_description/xacro/gazebo.urdf.xacro
deleted file mode 100644 (file)
index 977ae84..0000000
+++ /dev/null
@@ -1,27 +0,0 @@
-<?xml version="1.0"?>
-<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
-
-       <xacro:arg name="ignition" default="false"/>
-       
-       <!-- Gazebo Classic -->
-       <xacro:unless value="$(arg ignition)">
-               <gazebo>
-                       <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
-                               <robot_param>robot_description</robot_param>
-                               <robot_param_node>robot_state_publisher</robot_param_node>
-                               <parameters>$(find wam_description)/config/controller_manager.yaml</parameters>
-                       </plugin>
-               </gazebo>
-       </xacro:unless>
-       
-       <!-- Gazebo Ignition -->
-       <xacro:if value="$(arg ignition)">
-               <gazebo>
-                       <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
-                               <robot_param>robot_description</robot_param>
-                               <robot_param_node>robot_state_publisher</robot_param_node>
-                               <parameters>$(find wam_description)/config/controller_manager.yaml</parameters>
-                       </plugin>
-               </gazebo>
-       </xacro:if>
-</robot>
diff --git a/wam_description/xacro/gz_ros2_control.urdf.xacro b/wam_description/xacro/gz_ros2_control.urdf.xacro
new file mode 100644 (file)
index 0000000..e135ac7
--- /dev/null
@@ -0,0 +1,9 @@
+<?xml version="1.0"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <gazebo>
+               <plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
+                       <parameters>$(find wam_description)/config/controller_manager.yaml</parameters>
+               </plugin>
+       </gazebo>
+</robot>
index 418100d..80bb6cb 100644 (file)
@@ -1,26 +1,19 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <ros2_control name="GazeboSystem" type="system">
-       <!-- Gazebo Classic -->
-       <xacro:unless value="$(arg ignition)">
-               <hardware>
-                       <plugin>gazebo_ros2_control/GazeboSystem</plugin>
-               </hardware>
-       </xacro:unless>
-       <xacro:if value="$(arg ignition)">
-                <!-- Gazebo Ignition -->
-               <hardware>
-                       <plugin>ign_ros2_control/IgnitionSystem</plugin>
-               </hardware>
-       </xacro:if>
+  <ros2_control name="WamSystem" type="system">
+       <hardware>
+               <plugin>gz_ros2_control/GazeboSimSystem</plugin>
+       </hardware>
 
        <joint name="wam_joint_1">
                <command_interface name="effort">
                        <param name="min">${-1.8*42.00}</param>
                        <param name="max">${1.8*42.00}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">0.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -30,7 +23,9 @@
                        <param name="min">${-1.8*28.25}</param>
                        <param name="max">${1.8*28.25}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">-2.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -40,7 +35,9 @@
                        <param name="min">${-1.8*28.25}</param>
                        <param name="max">${1.8*28.25}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">0.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -50,7 +47,9 @@
                        <param name="min">${-1.6*18.00}</param>
                        <param name="max">${1.6*18.00}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">3.1</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -60,7 +59,9 @@
                        <param name="min">${-0.6*9.48}</param>
                        <param name="max">${0.6*9.48}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">0.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -70,7 +71,9 @@
                        <param name="min">${-0.6*9.48}</param>
                        <param name="max">${0.6*9.48}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">0.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
@@ -80,7 +83,9 @@
                        <param name="min">${-0.613*14.93}</param>
                        <param name="max">${0.613*14.93}</param>
                </command_interface>
-               <state_interface name="position"/>
+               <state_interface name="position">
+                       <param name="initial_value">0.0</param>
+               </state_interface>
                <state_interface name="velocity"/>
                <state_interface name="effort"/>
        </joint>
index 2db1b74..3da0c65 100644 (file)
@@ -12,9 +12,6 @@
 
   <xacro:property name="table_top_thickness" value="0.05"/>
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
-
   <!-- tabletop height is .55+.01+.025=.585 -->
   <link name="table_top_link">
     <inertial>
index fb4490e..c08050f 100644 (file)
@@ -6,8 +6,6 @@
   <xacro:arg name="table" default="false" />
   <xacro:arg name="bhand" default="false" />
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:include filename="$(find wam_description)/xacro/wam_base.urdf.xacro" />
   <xacro:include filename="$(find wam_description)/xacro/wam_j1.urdf.xacro" />
   <xacro:include filename="$(find wam_description)/xacro/wam_j2.urdf.xacro" />
@@ -30,7 +28,7 @@
   <xacro:wam_tool_plate parent="wam_link_7"/>
 
   <xacro:include filename="ros2_control.urdf.xacro"/>
-  <xacro:include filename="gazebo.urdf.xacro"/>
+  <xacro:include filename="gz_ros2_control.urdf.xacro"/>
        
   <xacro:if value="$(arg world)">
     <xacro:unless value="$(arg table)">
@@ -69,8 +67,8 @@
     <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.06" rpy="0.0 0.0 ${M_PI}" />
+      <!--origin xyz="0.0 0.013 0.0" rpy="${-pi/2} 0.0 0.0" /-->
+      <origin xyz="0.0 0.0 -0.06" rpy="0.0 0.0 ${pi}" />
     </joint>
   </xacro:if>
 
index 6de0675..275637e 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_base">
 
        <link name="wam_origin"/>
@@ -26,7 +24,7 @@
 <!--
        <link name="wam_link_0_inertial" />
        <joint name="wam_link_0_inertial_joint" type="fixed">
-               <origin xyz="-0.14071720 -0.02017671 -0.26604706" rpy="${M_PI/2} 0 ${M_PI/2}"/>
+               <origin xyz="-0.14071720 -0.02017671 -0.26604706" rpy="${pi/2} 0 ${pi/2}"/>
                <child link="wam_link_0_inertial"/>
                <parent link="wam_link_0"/>
        </joint>
@@ -46,7 +44,7 @@
        Inertial_Z -> Frame_X
 -->
                        <mass value="9.97059584"/>
-                       <origin xyz="-0.14071720 -0.02017671 -0.26604706"  rpy="${M_PI/2} 0 ${M_PI/2}"/>
+                       <origin xyz="-0.14071720 -0.02017671 -0.26604706"  rpy="${pi/2} 0 ${pi/2}"/>
                        <inertia ixx="0.10916849" ixy="0.00640270" ixz="0.02557874" iyy="0.18294303" iyz="0.00161433" izz="0.11760385"/>
                </inertial>
                <visual>
index a73bca6..0cb85eb 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j1" params="parent">
 
        <link name="wam_link_1">
@@ -18,7 +16,7 @@
                        <inertia ixx="0.13488033" ixy="-0.00213041" ixz="-0.00012485" iyy="0.11328369" iyz="0.00068555" izz="0.09046330"/>
                </inertial>
                <visual>
-                       <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${pi/2} 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>
@@ -27,7 +25,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${pi/2} 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>
@@ -45,7 +43,7 @@
        <joint name="wam_joint_1" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_1"/>
-               <origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+               <origin rpy="${-pi/2} 0 0" xyz="0.0 0.0 0.0"/>
                <axis xyz="0 -1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
index 77855b1..45188c8 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j2" params="parent">
 
        <link name="wam_link_2">
@@ -43,7 +41,7 @@
        <joint name="wam_joint_2" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_2"/>
-               <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+               <origin rpy="${pi/2} 0 0" xyz="0.0 0.0 0.0"/>
                <axis xyz="0 1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
index aeabe2a..6aa0b55 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j3" params="parent">
 
        <link name="wam_link_3">
@@ -17,7 +15,7 @@
                        <inertia ixx="0.05911077" ixy="-0.00249612" ixz="0.00000738" iyy="0.00324550" iyz="-0.00001767" izz="0.05927043"/>
                </inertial>
                <visual>
-                       <origin rpy="${M_PI/2} 0 0" xyz="-0.045 0.55 0.0"/>
+                       <origin rpy="${pi/2} 0 0" xyz="-0.045 0.55 0.0"/>
                        <geometry name="wam_link_3_visual">
                                <mesh filename="package://wam_description/meshes/wam3.stl" scale="1.0 1.0 1.0"/>
                        </geometry>
@@ -26,7 +24,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="${M_PI/2} 0 0" xyz="-0.045 0.55 0.0"/>
+                       <origin rpy="${pi/2} 0 0" xyz="-0.045 0.55 0.0"/>
                        <geometry name="wam_link_3_collision">
                                <mesh filename="package://wam_description/meshes/wam3.stl" scale="1.0 1.0 1.0"/>
                        </geometry>
@@ -46,7 +44,7 @@
        <joint name="wam_joint_3" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_3_virtual"/>
-               <origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.55"/>
+               <origin rpy="${-pi/2} 0 0" xyz="0.0 0.0 0.55"/>
                <axis xyz="0 -1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
index f1206ed..88be827 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j4" params="parent">
 
        <link name="wam_link_4">
@@ -17,7 +15,7 @@
                        <inertia ixx="0.01491672" ixy="0.00001741" ixz="-0.00150604" iyy="0.01482922" iyz="-0.00002109" izz="0.00294463"/>
                </inertial>
                <visual>
-                       <origin rpy="${-M_PI/2} 0 0" xyz="0.045 0.0 0.0"/>
+                       <origin rpy="${-pi/2} 0 0" xyz="0.045 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>
@@ -26,7 +24,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="${-M_PI/2} 0 0" xyz="0.045 0.0 0.0"/>
+                       <origin rpy="${-pi/2} 0 0" xyz="0.045 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>
@@ -46,7 +44,7 @@
        <joint name="wam_joint_4" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_4_virtual"/>
-               <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+               <origin rpy="${pi/2} 0 0" xyz="0.0 0.0 0.0"/>
                <axis xyz="0 1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
index d7770cd..5d2b54e 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j5" params="parent">
 
        <link name="wam_link_5">
@@ -17,7 +15,7 @@
                        <inertia ixx="0.00005029" ixy="0.00000020" ixz="-0.00000005" iyy="0.00007582" iyz="-0.00000359" izz="0.00006270"/>
                </inertial>
                <visual>
-                       <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${pi/2} 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>
@@ -26,7 +24,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${pi/2} 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>
@@ -42,7 +40,7 @@
        <joint name="wam_joint_5" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_5"/>
-               <origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.3"/>
+               <origin rpy="${-pi/2} 0 0" xyz="0.0 0.0 0.3"/>
                <axis xyz="0 -1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
index 96a3de3..8c21fb2 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-  <xacro:property name="M_PI" value="3.1415926535897931" />
-
   <xacro:macro name="wam_j6" params="parent">
 
        <link name="wam_link_6">
@@ -17,7 +15,7 @@
                        <inertia ixx="0.00055516" ixy="0.00000061" ixz="-0.00000074" iyy="0.00024367" iyz="-0.00004590" izz="0.00045358"/>
                </inertial>
                <visual>
-                       <origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${-pi/2} 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>
@@ -26,7 +24,7 @@
                        </material>
                </visual>
                <collision>
-                       <origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+                       <origin rpy="${-pi/2} 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>
@@ -42,7 +40,7 @@
        <joint name="wam_joint_6" type="revolute">
                <parent link="${parent}"/>
                <child link="wam_link_6"/>
-               <origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
+               <origin rpy="${pi/2} 0 0" xyz="0.0 0.0 0.0"/>
                <axis xyz="0 1 0"/>
 <!--
        from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
@@ -53,7 +51,7 @@
        friction: page 71
        effort: cable limit (page 75) x reduction (page 68)
 -->
-               <limit effort="${0.6*9.48}" lower="${-M_PI/2}" upper="${M_PI/2}" velocity="2.0"/>
+               <limit effort="${0.6*9.48}" lower="${-pi/2}" upper="${pi/2}" velocity="2.0"/>
                <!--dynamics friction="${3.0/7}"/-->
        </joint>
 
index b55d89f..36b966a 100644 (file)
@@ -2,8 +2,6 @@
 
 <robot name ="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
 
-       <xacro:property name="M_PI" value="3.1415926535897931" />
-
        <link name="world" />
 
        <xacro:include filename="$(find wam_description)/xacro/table.urdf.xacro" />