bug fixes

This commit is contained in:
litian.zhuang 2022-04-01 18:55:10 +08:00
parent 7643f0c7a2
commit cca937128f
8 changed files with 411 additions and 35 deletions

View File

@ -360,8 +360,8 @@ let_robot_go(){
echo -e "${Info} " echo -e "${Info} "
echo -e "${Info} 退出请输入Ctrl + c " echo -e "${Info} 退出请输入Ctrl + c "
echo && stty erase ^? && read -p "按回车键Enter开始" echo && stty erase ^? && read -p "按回车键Enter开始"
print_command "roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} enable_arm_tel:=false" print_command "roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} enable_arm_tel:=no"
roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} enable_arm_tel:="false" roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} arm_type_tel:=${ARMTYPE} enable_arm_tel:="no"
} }

View File

@ -1,5 +1,7 @@
<!--启动spark各种驱动--> <!--启动spark各种驱动-->
<launch> <launch>
<arg name="enable_arm_tel" default="false"/>
<arg name="arm_type_tel" default="uarm" doc="arm types [uarm, sagittarius_arm]"/>
<arg name="start_base" default="true"/> <arg name="start_base" default="true"/>
<arg name="start_camera" default="true"/> <arg name="start_camera" default="true"/>
@ -11,6 +13,8 @@
<include file="$(find spark_description)/launch/spark_description.launch"> <include file="$(find spark_description)/launch/spark_description.launch">
<arg name="camera_type_tel" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
<arg name="enable_arm_tel" value="$(arg enable_arm_tel)"/>
<arg name="arm_type_tel" value="$(arg arm_type_tel)"/>
</include> </include>
<!--启动底盘 --> <!--启动底盘 -->

View File

@ -10,7 +10,7 @@
<arg name="use_gui" default="false"/> <arg name="use_gui" default="false"/>
<arg name="publish_default_positions" default="true"/> <arg name="publish_default_positions" default="true"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_type_tel:=$(arg camera_type_tel) lidar_type_tel:=$(arg lidar_type_tel)"/> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_type_tel:=$(arg camera_type_tel) lidar_type_tel:=$(arg lidar_type_tel) arm_type_tel:=$(arg arm_type_tel) enable_arm_tel:=$(arg enable_arm_tel)"/>
<group if="$(eval arg('arm_type_tel')=='sagittarius_arm')"> <group if="$(eval arg('arm_type_tel')=='sagittarius_arm')">

View File

@ -9,8 +9,13 @@
<robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro"> <robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="camera_type_tel" default="astrapro"/> <xacro:arg name="camera_type_tel" default="astrapro"/>
<xacro:arg name="lidar_type_tel" default="3iroboticslidar2"/> <xacro:arg name="lidar_type_tel" default="3iroboticslidar2"/>
<xacro:arg name="enable_arm_tel" default="false"/>
<xacro:arg name="arm_type_tel" default="uarm"/>
<xacro:include filename="$(find spark_description)/urdf/spark_340.urdf.xacro"> <xacro:include filename="$(find spark_description)/urdf/spark_340.urdf.xacro">
<xacro:arg name="camera_type_tel" value="$(arg camera_type_tel)"/> <xacro:arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<xacro:arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <xacro:arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
<xacro:arg name="enable_arm_tel" value="$(arg enable_arm_tel)"/>
<xacro:arg name="arm_type_tel" value="$(arg arm_type_tel)"/>
</xacro:include> </xacro:include>
</robot> </robot>

View File

@ -7,8 +7,7 @@
--> -->
<robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro"> <robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="enable_arm_tel" default="no"/>
<xacro:arg name="enable_arm_tel" default="false"/>
<xacro:property name="enable_arm" value="$(arg enable_arm_tel)"/> <xacro:property name="enable_arm" value="$(arg enable_arm_tel)"/>
<xacro:arg name="arm_type_tel" default="uarm"/> <xacro:arg name="arm_type_tel" default="uarm"/>
@ -45,14 +44,13 @@
<xacro:if value="${camera == 'd435'}"> <xacro:if value="${camera == 'd435'}">
<xacro:include filename="$(find spark_description)/urdf/sensors/spark_d435.urdf.xacro"/> <xacro:include filename="$(find spark_description)/urdf/sensors/spark_d435.urdf.xacro"/>
</xacro:if> </xacro:if>
<xacro:if value="${robot_arm_type == 'sagittarius_arm' and enable_arm == 'yes'}">
<xacro:include filename="$(find sagittarius_descriptions)/urdf/spark_sagittarius_descriptions.urdf"/>
</xacro:if>
<xacro:if value="${robot_arm_type == 'uarm' and enable_arm == 'yes'}">
<xacro:include filename="$(find swiftpro)/urdf/spark_pro_model.xacro"/>
<xacro:if value="${enable_arm == 'true'}">
<xacro:if value="${robot_arm_type == 'sagittarius_arm'}">
<xacro:include filename="$(find sagittarius_descriptions)/urdf/spark_sagittarius_descriptions.urdf"/>
</xacro:if>
<xacro:if value="${robot_arm_type == 'uarm'}">
<xacro:include filename="$(find swiftpro)/urdf/spark_pro_model.xacro"/>
</xacro:if>
</xacro:if> </xacro:if>
</robot> </robot>

View File

@ -3,10 +3,15 @@
<!-- 启动哪种摄像机 --> <!-- 启动哪种摄像机 -->
<arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra, d435...]"/> <arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra, d435...]"/>
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<arg name="enable_arm_tel" default="no"/>
<arg name="arm_type_tel" default="uarm" doc="arm types [uarm, sagittarius_arm]"/>
<!--spark底盘驱动机器人描述,底盘,相机--> <!--spark底盘驱动机器人描述,底盘,相机-->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_type_tel" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
<arg name="enable_arm_tel" value="$(arg enable_arm_tel)"/>
<arg name="arm_type_tel" value="$(arg arm_type_tel)"/>
</include> </include>
<!-- 启动雷达 --> <!-- 启动雷达 -->
<include file="$(find lidar_driver_transfer)/launch/$(arg lidar_type_tel).launch"> <include file="$(find lidar_driver_transfer)/launch/$(arg lidar_type_tel).launch">

View File

@ -4,6 +4,8 @@ Panels:
Name: Displays Name: Displays
Property Tree Widget: Property Tree Widget:
Expanded: Expanded:
- /TF1
- /TF1/Status1
- /TF1/Frames1 - /TF1/Frames1
Splitter Ratio: 0.5 Splitter Ratio: 0.5
Tree Height: 140 Tree Height: 140
@ -65,6 +67,10 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Link Tree Style: Links in Alphabetic Order Link Tree Style: Links in Alphabetic Order
ar_tag_link:
Alpha: 1
Show Axes: false
Show Trail: false
base_footprint: base_footprint:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
@ -183,11 +189,51 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
lidar_bottom_screw_frame: lidar_link:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
lidar_link: Value: true
link1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link5:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link6:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_grasping_frame:
Alpha: 1
Show Axes: false
Show Trail: false
link_gripper_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_right:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
@ -202,11 +248,20 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
sagittarius_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
spark_stack: spark_stack:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
usb_cam_link:
Alpha: 1
Show Axes: false
Show Trail: false
Name: RobotModel Name: RobotModel
Robot Description: robot_description Robot Description: robot_description
TF Prefix: "" TF Prefix: ""
@ -219,9 +274,11 @@ Visualization Manager:
Frames: Frames:
All Enabled: false All Enabled: false
IMU_link: IMU_link:
Value: true Value: false
ar_tag_link:
Value: false
base_footprint: base_footprint:
Value: true Value: false
base_gyro_link: base_gyro_link:
Value: false Value: false
base_link: base_link:
@ -286,18 +343,38 @@ Visualization Manager:
Value: true Value: true
left_wheel_link: left_wheel_link:
Value: false Value: false
lidar_bottom_screw_frame:
Value: true
lidar_link: lidar_link:
Value: false Value: false
link1:
Value: false
link2:
Value: false
link3:
Value: false
link4:
Value: false
link5:
Value: false
link6:
Value: false
link_grasping_frame:
Value: false
link_gripper_left:
Value: false
link_gripper_right:
Value: false
odom: odom:
Value: true Value: false
right_wheel_link: right_wheel_link:
Value: false Value: false
room_base_link: room_base_link:
Value: false Value: false
sagittarius_base_link:
Value: false
spark_stack: spark_stack:
Value: false Value: false
usb_cam_link:
Value: false
Marker Alpha: 1 Marker Alpha: 1
Marker Scale: 1 Marker Scale: 1
Name: TF Name: TF
@ -363,8 +440,8 @@ Visualization Manager:
{} {}
left_wheel_link: left_wheel_link:
{} {}
lidar_bottom_screw_frame: lidar_link:
lidar_link: laser_frame:
{} {}
right_wheel_link: right_wheel_link:
{} {}
@ -372,8 +449,23 @@ Visualization Manager:
{} {}
spark_stack: spark_stack:
{} {}
laser_frame: sagittarius_base_link:
{} link1:
link2:
link3:
link4:
link5:
link6:
ar_tag_link:
{}
link_grasping_frame:
{}
link_gripper_left:
{}
link_gripper_right:
{}
usb_cam_link:
{}
Update Interval: 0 Update Interval: 0
Value: true Value: true
- Class: rviz/Image - Class: rviz/Image
@ -391,8 +483,8 @@ Visualization Manager:
- Alpha: 1 - Alpha: 1
Autocompute Intensity Bounds: true Autocompute Intensity Bounds: true
Autocompute Value Bounds: Autocompute Value Bounds:
Max Value: 24.765522003173828 Max Value: 2.4960973262786865
Min Value: -0.49686479568481445 Min Value: -0.11600154638290405
Value: true Value: true
Axis: Z Axis: Z
Channel Name: intensity Channel Name: intensity
@ -472,7 +564,7 @@ Visualization Manager:
Views: Views:
Current: Current:
Class: rviz/Orbit Class: rviz/Orbit
Distance: 4.319162368774414 Distance: 1.5491176843643188
Enable Stereo Rendering: Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549 Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1 Stereo Focal Distance: 1
@ -480,17 +572,17 @@ Visualization Manager:
Value: false Value: false
Field of View: 0.7853981852531433 Field of View: 0.7853981852531433
Focal Point: Focal Point:
X: 0.07904946058988571 X: 0.08042728900909424
Y: -0.19301681220531464 Y: -0.06426004320383072
Z: 0.4773929715156555 Z: 0.2163187712430954
Focal Shape Fixed Size: true Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806 Focal Shape Size: 0.05000000074505806
Invert Z Axis: false Invert Z Axis: false
Name: Current View Name: Current View
Near Clip Distance: 0.009999999776482582 Near Clip Distance: 0.009999999776482582
Pitch: 0.4103982150554657 Pitch: 0.39539822936058044
Target Frame: <Fixed Frame> Target Frame: <Fixed Frame>
Yaw: 2.0503973960876465 Yaw: 1.6903985738754272
Saved: ~ Saved: ~
Window Geometry: Window Geometry:
Displays: Displays:
@ -500,7 +592,7 @@ Window Geometry:
Hide Right Dock: true Hide Right Dock: true
Image: Image:
collapsed: false collapsed: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000017afc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000010c000000ab0000001600ffffff000000010000010f0000025efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003b80000003efc0100000002fb0000000800540069006d00650100000000000003b8000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002480000017a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 QMainWindow State: 000000ff00000000fd00000004000000000000016a0000017afc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000010c000000ab0000001600ffffff000000010000010f0000025efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003c80000003efc0100000002fb0000000800540069006d00650100000000000003c8000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002580000017a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection: Selection:
collapsed: false collapsed: false
Time: Time:
@ -509,6 +601,6 @@ Window Geometry:
collapsed: false collapsed: false
Views: Views:
collapsed: true collapsed: true
Width: 952 Width: 968
X: 72 X: 56
Y: 27 Y: 27

View File

@ -0,0 +1,272 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="swiftpro" >
<joint name="uarm_base_link_joint" type="fixed">
<origin xyz="0.044 0 0.138" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="Base" />
</joint>
<link name="Base">
<inertial>
<origin xyz="0.010476 0.000747 0.035226" rpy="0 0 0"/>
<mass value="1.886"/>
<inertia ixx="0.001196219" ixy="-0.000029358" ixz="0.000014859"
iyy="0.001147997" iyz="0.000016274" izz="0.001425617"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Base.STL"/>
</geometry>
<origin xyz = "0 0 0 " rpy = "0 0 0"/>
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<link name="Link1">
<inertial>
<origin xyz="-0.002175 0 0.029097" rpy="0 0 0"/>
<mass value="0.2141"/>
<inertia ixx="0.000496945" ixy="-0.000000082" ixz="-0.000002744"
iyy="0.000150389" iyz="-0.000000002" izz="0.000522487"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link1.STL"/>
</geometry>
<origin xyz = "0 0 -0.0723" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Base"/>
<child link="Link1"/>
<origin xyz= "0 0 0.0723" rpy = " 0 0 0" />
</joint>
<link name="Link2">
<inertial>
<origin xyz="-0.001071 0.001101 0.053193" rpy="0 0 0"/>
<mass value="0.026"/>
<inertia ixx="0.000061744" ixy="-0.000000025" ixz="-0.000000763"
iyy="0.000062096" iyz="-0.000001053" izz="0.000002942"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link2.STL"/>
</geometry>
<origin xyz = "-0.0132 0 -0.1056" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint2" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link1"/>
<child link="Link2"/>
<origin xyz= "0.0132 0 0.0333" rpy = " 0 0 0" />
</joint>
<link name="Link3">
<inertial>
<origin xyz="0.101948 -0.00022 0.011917" rpy="0 0 0"/>
<mass value="0.023"/>
<inertia ixx="0.000001982" ixy="0.000000483" ixz="-0.000005373"
iyy="0.000081264" iyz="0.000000008" izz="0.000080538"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link3.STL"/>
</geometry>
<origin xyz="-0.0132 0 -0.24767"/>
<material name="">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint3" type="revolute">
<axis xyz="0 1 0"/>
<parent link="Link2" />
<child link="Link3" />
<limit effort="1000" lower="-1.45" upper="1.45" velocity="0"/>
<origin xyz="0 0 0.14207 " rpy="0 0 0"/>
</joint>
<link name="Link4">
<inertial>
<origin xyz="-0.00235 0.013618 0.015458" rpy="0 0 0"/>
<mass value="0.003"/>
<inertia ixx="0.000000316" ixy="0.000000001" ixz="0.000000177"
iyy="0.000001679" iyz="-0.000000007" izz="0.000001378"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link4.STL"/>
</geometry>
<origin xyz = "-0.0132 0 -0.24767" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint4" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link2"/>
<child link="Link4"/>
<origin xyz= "0 0 0.14207" rpy = " 0 0 0" />
</joint>
<link name="Link5">
<inertial>
<origin xyz="0.000287 0.0157 0.072444" rpy="0 0 0"/>
<mass value="0.003"/>
<inertia ixx="0.000004841" ixy="0.000000000" ixz="0.000000023"
iyy="0.000004863" iyz="0.000000000" izz="0.000000023"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link5.STL"/>
</geometry>
<origin xyz = "0.0215 0 -0.1223" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint5" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link1"/>
<child link="Link5"/>
<origin xyz= "-0.0215 0 0.05001" rpy = " 0 0 0" />
</joint>
<link name="Link6">
<inertial>
<origin xyz="-0.014 -0.01391 -0.001062" rpy="0 0 0"/>
<mass value="0.003"/>
<inertia ixx="0.000000074" ixy="-0.000000060" ixz="0.000000055"
iyy="0.000000951" iyz="-0.000000004" izz="0.000000923"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link6.STL"/>
</geometry>
<origin xyz = "-0.0132 0 -0.1056" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint6" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link1"/>
<child link="Link6"/>
<origin xyz= "0.0132 0 0.0333" rpy = " 0 0 0" />
</joint>
<link name="Link7">
<inertial>
<origin xyz="-0.001242 -0.013867 0.083246" rpy="0 0 0"/>
<mass value="0.003"/>
<inertia ixx="0.000007052" ixy="0.000000003" ixz="0.000000055"
iyy="0.000007058" iyz="0.000000117" izz="0.000000039"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link7.STL"/>
</geometry>
<origin xyz = "0.0323 0 -0.10258" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint7" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link6"/>
<child link="Link7"/>
<origin xyz= "-0.0455 0 -0.00301" rpy = " 0 0 0" />
</joint>
<link name="Link8">
<inertial>
<origin xyz="0.027288 0.001085 -0.007344" rpy="0 0 0"/>
<mass value="0.012"/>
<inertia ixx="0.000002184" ixy="0.000000020" ixz="-0.000000207"
iyy="0.000002992" iyz="0.000000371" izz="0.000001832"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Gripper.STL"/>
</geometry>
<origin xyz = "-0.17201 0 -0.24651" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint8" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link3"/>
<child link="Link8"/>
<origin xyz= "0.15852 0 0" rpy = " 0 0 0" />
</joint>
<link name="Link9">
<inertial>
<origin xyz="-0.079305 0.0157 -0.000043" rpy="0 0 0"/>
<mass value="0.003"/>
<inertia ixx="0.000000022" ixy="0.000000000" ixz="-0.000000002"
iyy="0.000006517" iyz="0.000000000" izz="0.000006497"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Link9.STL"/>
</geometry>
<origin xyz = "-0.19941 0 -0.27471" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>
<joint name="Joint9" type="revolute">
<axis xyz="0 1 0"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link8"/>
<child link="Link9"/>
<origin xyz= "0.02741 0 0.02703" rpy = " 0 0 0" />
</joint>
</robot>