<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
- <node unless="$(arg table)" name="rviz" pkg="rviz" type="rviz" args="-d $(find wam_description)/rviz/urdf.rviz" required="true"/>
- <node if="$(arg table)" name="rviz" pkg="rviz" type="rviz" args="-d $(find wam_description)/rviz/urdf.rviz -f world" required="true"/>
+ <node unless="$(arg table)" name="rviz" pkg="rviz" type="rviz" args="-d $(find wam_description)/rviz/display.rviz" required="true"/>
+ <node if="$(arg table)" name="rviz" pkg="rviz" type="rviz" args="-d $(find wam_description)/rviz/display.rviz -f world" required="true"/>
</launch>
<arg name="table" default="true"/>
<arg name="bhand" default="true"/>
-
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="$(arg paused)"/>
<arg name="headless" value="$(arg headless)"/>
- <launch>
+<launch>
<arg name="table" default="true"/>
<arg name="bhand" default="true"/>
<arg name="world" default="false"/>
+++ /dev/null
-Panels:
- - Class: rviz/Displays
- Help Height: 78
- Name: Displays
- Property Tree Widget:
- Expanded:
- - /Global Options1
- - /Status1
- - /Grid1
- - /RobotModel1
- - /RobotModel1/Links1
- - /RobotModel1/Links1/bhand_base_link1
- - /RobotModel1/Links1/wam_link_01
- - /RobotModel1/Links1/wam_link_11
- - /RobotModel1/Links1/wam_link_21
- - /RobotModel1/Links1/wam_link_31
- - /RobotModel1/Links1/wam_link_41
- - /RobotModel1/Links1/wam_link_51
- - /RobotModel1/Links1/wam_link_61
- - /RobotModel1/Links1/wam_link_71
- - /RobotModel1/Links1/wam_link_base1
- - /RobotModel1/Links1/wam_link_footprint1
- - /RobotModel1/Links1/wam_origin1
- - /RobotModel1/Links1/wam_tool_plate1
- - /RobotModel1/Links1/world1
- Splitter Ratio: 0.721154
- Tree Height: 454
- - Class: rviz/Selection
- Name: Selection
- - Class: rviz/Tool Properties
- Expanded:
- - /2D Pose Estimate1
- - /2D Nav Goal1
- - /Publish Point1
- Name: Tool Properties
- Splitter Ratio: 0.588679
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
- - Class: rviz/Time
- Experimental: false
- Name: Time
- SyncMode: 0
- SyncSource: ""
-Visualization Manager:
- Class: ""
- Displays:
- - Alpha: 0.5
- Cell Size: 1
- Class: rviz/Grid
- Color: 160; 160; 164
- Enabled: true
- Line Style:
- Line Width: 0.03
- Value: Lines
- Name: Grid
- Normal Cell Count: 0
- Offset:
- X: 0
- Y: 0
- Z: 0
- Plane: XY
- Plane Cell Count: 10
- Reference Frame: <Fixed Frame>
- Value: true
- - Alpha: 0.3
- Class: rviz/RobotModel
- Collision Enabled: false
- Enabled: true
- Links:
- All Links Enabled: true
- Expand Joint Details: false
- Expand Link Details: false
- Expand Tree: false
- Link Tree Style: Links in Alphabetic Order
- bhand_base_link:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- bhand_finger1_link_1:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger1_link_2:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger1_link_3:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger2_link_1:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger2_link_2:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger2_link_3:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger3_link_1:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger3_link_2:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_finger3_link_3:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- bhand_origin:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- leg1_link:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- leg2_link:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- leg3_link:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- leg4_link:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- table_top_link:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- wam_link_0:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_1:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_2:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_3:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_3_virtual:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- wam_link_4:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_4_virtual:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- wam_link_5:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_6:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_7:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Value: true
- wam_link_base:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- wam_link_footprint:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- wam_origin:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- wam_tool_plate:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- world:
- Alpha: 1
- Show Axes: true
- Show Trail: false
- Name: RobotModel
- Robot Description: robot_description
- TF Prefix: ""
- Update Interval: 0
- Value: true
- Visual Enabled: true
- Enabled: true
- Global Options:
- Background Color: 48; 48; 48
- Fixed Frame: world
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz/FocusCamera
- - Class: rviz/Measure
- - Class: rviz/SetInitialPose
- Topic: /initialpose
- - Class: rviz/SetGoal
- Topic: /move_base_simple/goal
- - Class: rviz/PublishPoint
- Single click: true
- Topic: /clicked_point
- Value: true
- Views:
- Current:
- Class: rviz/Orbit
- Distance: 0.776736
- Enable Stereo Rendering:
- Stereo Eye Separation: 0.06
- Stereo Focal Distance: 1
- Swap Stereo Eyes: false
- Value: false
- Focal Point:
- X: -0.948974
- Y: 0.396795
- Z: 1.84864
- Name: Current View
- Near Clip Distance: 0.01
- Pitch: 0.0148
- Target Frame: <Fixed Frame>
- Value: Orbit (rviz)
- Yaw: 2.54046
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 741
- Hide Left Dock: false
- Hide Right Dock: true
- QMainWindow State: 000000ff00000000fd00000004000000000000013c00000251fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003600000251000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000251fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000036000002510000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000024700fffffffb0000000800540069006d006501000000000000045000000000000000000000036e0000025100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- Selection:
- collapsed: false
- Time:
- collapsed: false
- Tool Properties:
- collapsed: false
- Views:
- collapsed: true
- Width: 1200
- X: 82
- Y: 0
<?xml version="1.0"?>
-<robot name="table" xmlns:xacro="http://ros.org/wiki/xacro" >
+<robot name="table" xmlns:xacro="http://www.ros.org/wiki/xacro" >
- <property name="table_height" value="0.55" />
- <property name="table_width" value="1.0" />
- <property name="table_depth" value="2.0" />
- <property name="leg_radius" value="0.02" />
- <property name="table_x" value="0.98" />
- <property name="table_y" value="0.0" />
- <property name="table_z" value="0.0" />
+ <xacro:property name="table_height" value="0.55" />
+ <xacro:property name="table_width" value="1.0" />
+ <xacro:property name="table_depth" value="2.0" />
+ <xacro:property name="leg_radius" value="0.02" />
+ <xacro:property name="table_x" value="0.98" />
+ <xacro:property name="table_y" value="0.0" />
+ <xacro:property name="table_z" value="0.0" />
- <property name="table_top_thickness" value="0.05"/>
+ <xacro:property name="table_top_thickness" value="0.05"/>
- <property name="M_PI" value="3.1415926535897931" />
+ <xacro:property name="M_PI" value="3.1415926535897931" />
<!-- tabletop height is .55+.01+.025=.585 -->
<?xml version="1.0"?>
-<robot name="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find wam_description)/xacro/wam_base.urdf.xacro" />
<xacro:include filename="$(find wam_description)/xacro/wam_j1.urdf.xacro" />
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" >
- <robotNamespace>wam</robotNamespace>
+ <!--robotNamespace>wam</robotNamespace-->
<!-- Custom plugin -->
<!-- robotSimType>wam_gazebo_ros_control/WamRobotHWSim</robotSimType -->
<?xml version="1.0"?>
-<robot name="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />
<?xml version="1.0"?>
-<robot name ="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name ="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
- <property name="M_PI" value="3.1415926535897931" />
+ <xacro:property name="M_PI" value="3.1415926535897931" />
<link name="world" />
<?xml version="1.0"?>
-<robot name ="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name ="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="world" />
<child link="wam_link_1"/>
<origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 -1 0"/>
- <limit effort="30" lower="-2.6" upper="2.6" velocity="2.0"/>
- <!-- <safety_controller k_velocity="0.5"/> -->
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.9" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${1.8*42.00}" lower="-2.6" upper="2.6" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<transmission name="j1_transmission">
</joint>
<actuator name="j1_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>42.0</mechanicalReduction>
</actuator>
</transmission>
<child link="wam_link_2"/>
<origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
- <limit effort="30" lower="-2.0" upper="2.0" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.25" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${1.8*28.25}" lower="-2.0" upper="2.0" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<transmission name="j2_transmission">
</joint>
<actuator name="j2_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>28.25</mechanicalReduction>
</actuator>
</transmission>
<child link="wam_link_3_virtual"/>
<origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.55"/>
<axis xyz="0 1 0"/>
- <limit effort="30" lower="-2.8" upper="2.8" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.75" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${1.8*28.25}" lower="-2.8" upper="2.8" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<joint name="wam_joint_3_virtual" type="fixed">
</joint>
<actuator name="j3_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>28.25</mechanicalReduction>
</actuator>
</transmission>
<child link="wam_link_4_virtual"/>
<origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
- <limit effort="35" lower="-0.9" upper="3.1" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.4" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${1.6*18.00}" lower="-0.9" upper="3.1" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<joint name="wam_joint_4_virtual" type="fixed">
<child link="wam_link_5"/>
<origin rpy="${-M_PI/2} 0 0" xyz="0.0 0.0 0.3"/>
<axis xyz="0 1 0"/>
- <limit effort="30" lower="-4.8" upper="1.3" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.25" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${0.6*9.48}" lower="-4.76" upper="1.24" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<transmission name="j5_transmission">
</joint>
<actuator name="j5_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>9.48</mechanicalReduction>
</actuator>
</transmission>
<child link="wam_link_6"/>
<origin rpy="${M_PI/2} 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
- <limit effort="30" lower="-1.6" upper="1.6" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.05" friction="0.0"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ 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"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<transmission name="j6_transmission">
</joint>
<actuator name="j6_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>9.48</mechanicalReduction>
</actuator>
</transmission>
<child link="wam_link_7"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.06"/>
<axis xyz="0 0 1"/>
- <limit effort="30" lower="-2.2" upper="2.2" velocity="2.0"/>
- <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
- <dynamics damping="0.05" friction="${3.0/7}"/>
+<!--
+ from Barrett Technology, Inc, WAM Arm User's Manual, 2008, Document:
+ D1001, Version: AH.00
+
+ lower and upper limits: page 71
+ velocity: page 17
+ friction: page 71
+ effort: cable limit (page 75) x reduction (page 68)
+-->
+ <limit effort="${0.613*14.93}" lower="-3.0" upper="3.0" velocity="2.0"/>
+ <!--dynamics friction="${3.0/7}"/-->
</joint>
<transmission name="j7_transmission">
</joint>
<actuator name="j7_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
- <mechanicalReduction>1</mechanicalReduction>
+ <mechanicalReduction>14.93</mechanicalReduction>
</actuator>
</transmission>
<?xml version="1.0"?>
-<robot name ="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name ="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
- <property name="M_PI" value="3.1415926535897931" />
+ <xacro:property name="M_PI" value="3.1415926535897931" />
<link name="world" />
<?xml version="1.0"?>
-<robot name ="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name ="wam" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="world" />