i should be learning

yet i am refactoring
this is not a poem
pain.
This commit is contained in:
Bastian Hofmann
2022-03-27 01:05:50 +01:00
parent 435332c054
commit 2d2bc89a6b
23 changed files with 411 additions and 667 deletions

View File

@@ -149,6 +149,8 @@ def launch_setup(context, *args, **kwargs):
robot_description,
robot_description_semantic,
kinematics_yaml,
planning,
use_sim_time
],
)

View File

@@ -27,6 +27,7 @@
<joint name="link3_rot" value="0"/>
</group_state>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="table" link2="base_bottom" reason="Adjacent"/>
<disable_collisions link1="base_bottom" link2="base_top" reason="Adjacent"/>
<disable_collisions link1="base_top" link2="link1_full" reason="Adjacent"/>
<disable_collisions link1="base_top" link2="link2_bottom" reason="Never"/>

BIN
src/iisy_config/stl/table.stl Executable file

Binary file not shown.

View File

@@ -5,6 +5,18 @@
<link name="world"/>
<link name="base_link"/>
<link name="table">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/table.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/table.stl"/>
</geometry>
</visual>
</link>
<link name="base_bottom">
<collision>
<geometry>
@@ -22,7 +34,6 @@
<mass value="6"/>
<inertia ixx="1.277905" ixy="0.0" ixz="0.138279" iyy="3.070705" iyz="0.0" izz="3.284356"/>
</inertial>
</link>
<link name="base_top">
<collision>
@@ -138,8 +149,8 @@
<mass value="0.8"/>
<inertia ixx="0.228470" ixy="0.0" ixz="0.0" iyy="0.137641" iyz="0.0" izz="0.252003"/>
</inertial>
</link>
<joint type="fixed" name="world_base_link_fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="world"/>
@@ -148,6 +159,11 @@
<joint type="fixed" name="base_base_link_fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="table"/>
</joint>
<joint type="fixed" name="table_link_fixed">
<origin xyz="0 0 1" rpy="0 0 0"/>
<parent link="table"/>
<child link="base_bottom"/>
</joint>
<joint type="continuous" name="base_rot">