bhand_controller:
ros__parameters:
+ type: position_controllers/JointGroupPositionController
joints:
- bhand_finger1_joint_2
- bhand_finger2_joint_2
- bhand_finger3_joint_2
- bhand_spread
-
+
--- /dev/null
+joint_state_broadcaster:
+ ros__parameters:
+ type: joint_state_broadcaster/JointStateBroadcaster
<!--******************************************************************************
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
<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>
<!--******************************************************************************
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>
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
--- /dev/null
+- 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
+++ /dev/null
-prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
-
-set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
<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>
+<!--******************************************************************************
+ 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>
+++ /dev/null
-<!--******************************************************************************
- 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>
<?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>
<?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">
<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>
</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>
<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>
</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>
<!--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"/>
<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"/>
+++ /dev/null
-<?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>
--- /dev/null
+<?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>
<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>
)
install(PROGRAMS
- scripts/set_home.sh
scripts/step.sh
scripts/step_home.sh
scripts/step_zero.sh
computed_torque_controller:
ros__parameters:
+ type: effort_controllers/ComputedTorqueController
joints:
- wam_joint_1
- wam_joint_2
--- /dev/null
+joint_state_broadcaster:
+ ros__parameters:
+ type: joint_state_broadcaster/JointStateBroadcaster
pid_independent_joint_controller:
ros__parameters:
- joints:
+ type: pid_controller/PidController
+ dof_names:
- wam_joint_1
- wam_joint_2
- wam_joint_3
- 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}
pid_plus_gravity_controller:
ros__parameters:
+ type: effort_controllers/PidPlusGravityController
joints:
- wam_joint_1
- wam_joint_2
<!--******************************************************************************
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
<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>
<!--******************************************************************************
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)"/>
<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>
<!--******************************************************************************
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>
<!--******************************************************************************
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
<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>
+++ /dev/null
-#!/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"
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
#!/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
#!/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
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
--- /dev/null
+- 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
+++ /dev/null
-prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
-
-set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
+<!--******************************************************************************
+ 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>
+++ /dev/null
-<!--******************************************************************************
- 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>
<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>
+++ /dev/null
-#!/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]"
+++ /dev/null
-#!/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]"
+++ /dev/null
-<?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>
--- /dev/null
+<?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>
<?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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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" />
<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)">
<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>
<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"/>
<!--
<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>
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>
<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">
<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>
</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>
<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:
<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">
<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:
<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">
<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>
</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>
<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:
<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">
<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>
</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>
<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:
<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">
<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>
</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>
<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:
<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">
<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>
</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>
<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:
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>
<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" />