mirror of
https://github.com/bjoernellens1/bot_mini_description.git
synced 2024-11-24 16:15:07 +00:00
update laser joint pos
This commit is contained in:
parent
64b0d2c5c4
commit
b815ef597d
@ -70,10 +70,10 @@
|
|||||||
<!-- right wheel joint -->
|
<!-- right wheel joint -->
|
||||||
<!-- fixed wheel joint for testing, type was continuous -->
|
<!-- fixed wheel joint for testing, type was continuous -->
|
||||||
<joint name="${prefix}right_wheel_joint" type="continuous">
|
<joint name="${prefix}right_wheel_joint" type="continuous">
|
||||||
<origin xyz="0 -0.125 ${z_offset}" rpy="${PI / 2} 0 0" />
|
<origin xyz="0 {-0.125 - wheel_len /2} ${z_offset}" rpy="${PI / 2} 0 0" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}right_wheel" />
|
<child link="${prefix}right_wheel" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
<limit effort="1" velocity="20" />
|
<limit effort="1" velocity="20" />
|
||||||
<joint_properties friction="0.0"/>
|
<joint_properties friction="0.0"/>
|
||||||
</joint>
|
</joint>
|
||||||
@ -81,7 +81,7 @@
|
|||||||
<!-- right wheel Link -->
|
<!-- right wheel Link -->
|
||||||
<link name="${prefix}right_wheel">
|
<link name="${prefix}right_wheel">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 -{wheel_len /2} 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="package://bot_mini_description/mesh/wheel_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
@ -105,10 +105,10 @@
|
|||||||
<!-- fixed wheel joint for testing, type was continuous -->
|
<!-- fixed wheel joint for testing, type was continuous -->
|
||||||
<!-- left wheel joint -->
|
<!-- left wheel joint -->
|
||||||
<joint name="${prefix}left_wheel_joint" type="continuous">
|
<joint name="${prefix}left_wheel_joint" type="continuous">
|
||||||
<origin xyz="0 0.125 ${z_offset}" rpy="${PI / 2} 0 0" />
|
<origin xyz="0 {0.125 + wheel_len /2} ${z_offset}" rpy="${PI / 2} 0 0" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}left_wheel" />
|
<child link="${prefix}left_wheel" />
|
||||||
<axis xyz="0 0 -1" />
|
<axis xyz="0 0 1" />
|
||||||
<limit effort="1" velocity="20" />
|
<limit effort="1" velocity="20" />
|
||||||
<joint_properties friction="0.0" />
|
<joint_properties friction="0.0" />
|
||||||
</joint>
|
</joint>
|
||||||
@ -116,7 +116,7 @@
|
|||||||
<!-- left wheel Link -->
|
<!-- left wheel Link -->
|
||||||
<link name="${prefix}left_wheel">
|
<link name="${prefix}left_wheel">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 {wheel_len /2} 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
@ -125,7 +125,7 @@
|
|||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 {wheel_len /2} 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
|
Loading…
Reference in New Issue
Block a user