Skip to content

Commit

Permalink
Add package:// and http:// option.
Browse files Browse the repository at this point in the history
  • Loading branch information
maxpolzin committed Feb 4, 2024
1 parent 27389e9 commit c53ce54
Show file tree
Hide file tree
Showing 4 changed files with 85 additions and 190 deletions.
5 changes: 2 additions & 3 deletions helix_bringup/launch/helix_bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,9 @@ def generate_launch_description():

ld = LaunchDescription()



robot_description = os.path.join(get_package_share_directory("helix_description"), "urdf", "helix.urdf.xacro")
robot_description_config = xacro.process_file(robot_description)
robot_description_config = xacro.process_file(robot_description, mappings={'mesh_url' : 'http://127.0.0.1'})
# robot_description_config = xacro.process_file(robot_description, mappings={'mesh_url' : 'package://helix_description'})

robot_state_publisher = Node(
package="robot_state_publisher",
Expand Down
159 changes: 28 additions & 131 deletions helix_description/urdf/dynamixel_block.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:arg name="mesh_url" default="package://helix_description" />

<!-- Import Rviz colors -->
<xacro:include filename="$(find helix_description)/urdf/dynamixel_block.material.xacro" />

Expand All @@ -24,14 +26,14 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_body"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -46,14 +48,14 @@
<visual>
<origin xyz="-0.03 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_0_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_0_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.03 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_0_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_0_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -69,14 +71,14 @@
<visual>
<origin xyz="-0.03 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_1_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.03 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_1_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -90,14 +92,14 @@
<visual>
<origin xyz="-0.0 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_2_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_2_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.0 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_2_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_2_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -111,14 +113,14 @@
<visual>
<origin xyz="-0.0 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_3_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_3_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.0 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_3_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_3_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -132,14 +134,14 @@
<visual>
<origin xyz="0.03 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_4_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="0.03 -0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_4_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -153,14 +155,14 @@
<visual>
<origin xyz="0.03 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_5_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="0.03 -0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_5_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -174,14 +176,14 @@
<visual>
<origin xyz="0.03 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_6_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_6_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="0.03 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_6_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_6_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -195,14 +197,14 @@
<visual>
<origin xyz="0.03 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_7_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_7_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="0.03 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_7_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_7_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -216,14 +218,14 @@
<visual>
<origin xyz="-0.0 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_8_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_8_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.0 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_8_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_8_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -237,14 +239,14 @@
<visual>
<origin xyz="-0.0 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_9_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_9_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.0 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_9_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_9_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -258,14 +260,14 @@
<visual>
<origin xyz="-0.03 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_10_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_10_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.03 0.037 -0.08475" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_10_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_10_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand All @@ -279,14 +281,14 @@
<visual>
<origin xyz="-0.03 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_11_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_11_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dynamixel_horn"/>
</visual>
<collision>
<origin xyz="-0.03 0.037 -0.01425" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find helix_description)/meshes/horn_11_1.stl" scale="0.001 0.001 0.001"/>
<mesh filename="$(arg mesh_url)/meshes/horn_11_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Expand Down Expand Up @@ -376,110 +378,5 @@
<axis xyz="0.0 -1.0 0.0"/>
</joint>



<!-- Joint 1 -->

<!-- <joint name="dynamixel0to_delete" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0.012 0.0 0.017" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit velocity="4.8" effort="1" lower="-2.82743338823" upper="2.82743338823" />
</joint> -->



<!-- Link 1 -->
<!-- <link name="link1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04" />
<mass value="7.9119962e-02" />
<inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07"
iyy="2.1898364e-05" iyz="0.0"
izz="1.9267361e-05" />
</inertial>
</link> -->



<!-- Link 2 -->
<!-- <link name="link2">
<visual>
<origin xyz="0 0 0.019" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin xyz="0 0 0.019" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<origin xyz="-3.0184870e-04 5.4043684e-04 0.047433464e-02" />
<mass value="9.8406837e-02" />
<inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07"
iyy="3.2689329e-05" iyz="2.8511935e-08"
izz="1.8850320e-05" />
</inertial>
</link> -->

<!-- Joint 2 -->
<!-- <joint name="dynamixel1" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin xyz="0.0 0.0 0.0595" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit velocity="4.8" effort="1" lower="-1.79070781255" upper="1.57079632679" />
</joint> -->

<!-- Link 3 -->
<!-- <link name="link3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://helix_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01" />
<mass value="1.3850917e-01" />
<inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05"
iyy="3.4290447e-04" iyz="-1.5717516e-06"
izz="6.0346498e-05" />
</inertial>
</link> -->



</xacro:macro>
</robot>
5 changes: 1 addition & 4 deletions helix_description/urdf/helix.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,17 +1,14 @@
<?xml version="1.0"?>
<robot name="helix_description" xmlns:xacro="http://ros.org/wiki/xacro">

<!-- Uncomment this to show dynamixel!-->
<xacro:include filename="$(find helix_description)/urdf/dynamixel_block.xacro" />
<xacro:include filename="$(find helix_description)/urdf/dynamixel_block.ros2_control.xacro" />

<!-- Uncomment this to show hand!-->
<xacro:include filename="$(find helix_description)/urdf/helix.xacro" />
<xacro:include filename="$(find helix_description)/urdf/helix.xacro" />


<link name="world"/>

<!-- Uncomment this to show dynamixels!-->
<xacro:dynamixel_block_ros2_control name="dynamixel_block_ros2_control" />

<xacro:dynamixel_block parent="world">
Expand Down
Loading

0 comments on commit c53ce54

Please sign in to comment.