Skip to content

Commit

Permalink
add 280 ros camera&pump urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Nov 14, 2023
1 parent 1993b7b commit 79ba991
Show file tree
Hide file tree
Showing 2 changed files with 303 additions and 0 deletions.
25 changes: 25 additions & 0 deletions mycobot_280/mycobot_280pi/launch/test_camera_flange_pump.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<launch>
<!-- <arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" /> -->
<!-- Load file model ,加载文件模型-->
<arg name="model" default="$(find mycobot_description)/urdf/mycobot_pi/mycobot_with_camera_flange_pump.urdf"/>

<arg name="rvizconfig" default="$(find mycobot_280pi)/config/mycobot.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF,将值合并到TF -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui">
<!-- <param name="use_gui" value="$(arg gui)" /> -->
<!-- <rosparam param="source_list" subst_value="true">["joint_states"]</rosparam> -->
</node>
<!-- Open control script -->
<!-- <node name="control_slider" pkg="mycobot_280" type="slider_control.py">
<param name="port" type="string" value="$(arg port)" />
<param name="baud" type="int" value="$(arg baud)" />
</node> -->
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,278 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter" >

<xacro:property name="width" value=".2" />


<link name="g_base">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/G_base.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03" rpy = "0 0 1.5708"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/G_base.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03" rpy = "0 0 1.5708"/>
</collision>
</link>

<link name="pump_box">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/pump_box.dae"/>
</geometry>
<origin xyz = "0.0 -0.15 -0.0" rpy = "1.5708 3.14159 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/pump_box.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03" rpy = "0 0 1.5708"/>
</collision>
</link>

<link name="joint1">
<visual>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint1_pi.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint1_pi.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="joint2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -1.5708"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -1.5708"/>
</collision>
</link>


<link name="joint3">
<visual>
<geometry>

<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -1.5708 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -1.5708 0"/>
</collision>
</link>


<link name="joint4">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -1.5708 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -1.5708 0"/>
</collision>
</link>




<link name="joint5">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = " 0 -1.5708 1.5708"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = " 0 -1.5708 1.5708"/>
</collision>
</link>


<link name="joint6">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</collision>
</link>


<link name="joint6_flange">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pi/joint7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="camera_flange">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/camera_flange.dae"/>
</geometry>
<origin xyz = "0.024 -0.008 0.0 " rpy = " 0 3.14159 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/camera_flange.dae"/>
</geometry>
<origin xyz = "0.024 -0.008 0.0 " rpy = " 0 3.14159 0"/>
</collision>
</link>

<link name="pump_head">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/pump_head.dae"/>
</geometry>
<origin xyz = "0.0 0.008 0.009 " rpy = " 1.5708 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pi/pump_head.dae"/>
</geometry>
<origin xyz = "0.0 0.008 0.009 " rpy = " 1.5708 0 0"/>
</collision>
</link>



<joint name="g_base_to_joint1" type="fixed">
<axis xyz="0 0 0"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="g_base"/>
<child link="joint1"/>
<origin xyz= "0 0 0" rpy = "0 0 0"/>
</joint>

<joint name="g_base_to_pump_box" type="fixed">
<axis xyz="0 0 0"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="g_base"/>
<child link="pump_box"/>
<origin xyz= "0 0 0" rpy = "0 0 0"/>
</joint>

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint1"/>
<child link="joint2"/>
<origin xyz= "0 0 0.13956" rpy = "0 0 0"/>
</joint>


<joint name="joint3_to_joint2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint2"/>
<child link="joint3"/>
<origin xyz= "0 0 -0.001" rpy = "0 1.5708 -1.5708"/>
</joint>


<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= " -0.1104 0 0 " rpy = "0 0 0"/>
</joint>


<joint name="joint5_to_joint4" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint4"/>
<child link="joint5"/>
<origin xyz= "-0.096 0 0.06462" rpy = "0 0 -1.5708"/>
</joint>

<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint5"/>
<child link="joint6"/>
<origin xyz= "0 -0.07318 0" rpy = "1.5708 -1.5708 0"/>
</joint>

<joint name="joint6output_to_joint6" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="joint6"/>
<child link="joint6_flange"/>
<origin xyz= "0 0.0456 0" rpy = "-1.5708 0 0"/>
</joint>

<joint name="joint6output_to_camera_flange" type="fixed">
<!-- <axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/> -->
<parent link="joint6_flange"/>
<child link="camera_flange"/>
<!-- <origin xyz= "0 0.0 0" rpy = "-1.5708 0 0"/> -->
<origin xyz= "0 0 0.01" rpy = "1.579 0 0"/>
</joint>

<joint name="joint6output_to_pump_head" type="fixed">
<!-- <axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/> -->
<parent link="camera_flange"/>
<child link="pump_head"/>
<!-- <origin xyz= "0 0.0 0" rpy = "-1.5708 0 0"/> -->
<origin xyz= "0 0 0.01" rpy = "-1.579 0 0"/>
</joint>

</robot>

0 comments on commit 79ba991

Please sign in to comment.