mirror of
https://github.com/bjoernellens1/cps_loki_description.git
synced 2024-11-21 23:23:49 +00:00
update
This commit is contained in:
parent
5dbf1b2518
commit
966b49d3d8
@ -23,43 +23,6 @@
|
|||||||
<xacro:property name="caster_wheel_offset_x" value="0.075"/>
|
<xacro:property name="caster_wheel_offset_x" value="0.075"/>
|
||||||
<xacro:property name="caster_wheel_offset_z" value="${wheel_offset_z - wheel_radius + caster_wheel_radius}"/>
|
<xacro:property name="caster_wheel_offset_z" value="${wheel_offset_z - wheel_radius + caster_wheel_radius}"/>
|
||||||
<xacro:property name="chassis_offset" value="0.065"/>
|
<xacro:property name="chassis_offset" value="0.065"/>
|
||||||
|
|
||||||
<!-- Materials -->
|
|
||||||
<!-- <material name="white">
|
|
||||||
<color rgba="1 1 1 1" />
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="orange">
|
|
||||||
<color rgba="1 0.3 0.1 1"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="blue">
|
|
||||||
<color rgba="0.2 0.2 1 1"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="black">
|
|
||||||
<color rgba="0 0 0 1"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="red">
|
|
||||||
<color rgba="1 0 0 1"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="green">
|
|
||||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="grey">
|
|
||||||
<color rgba="0.6 0.6 0.6 1.0"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="grey2">
|
|
||||||
<color rgba="0.9 0.9 0.9 1.0"/>
|
|
||||||
</material>
|
|
||||||
|
|
||||||
<material name="lightGrey">
|
|
||||||
<color rgba="0.6 0.6 0.6 1.0"/>
|
|
||||||
</material> -->
|
|
||||||
|
|
||||||
<!-- Base Link -->
|
<!-- Base Link -->
|
||||||
<link name="${prefix}base_link">
|
<link name="${prefix}base_link">
|
||||||
@ -80,7 +43,7 @@
|
|||||||
<joint name="${prefix}chassis_joint" type="fixed">
|
<joint name="${prefix}chassis_joint" type="fixed">
|
||||||
<parent link="${prefix}base_link"/>
|
<parent link="${prefix}base_link"/>
|
||||||
<child link="${prefix}chassis"/>
|
<child link="${prefix}chassis"/>
|
||||||
<origin xyz="${-chassis_length/2 + 0.065} 0 ${wheel_radius - wheel_offset_z}"/>
|
<origin xyz="${-chassis_length/2 + chassis_offset} 0 ${wheel_radius - wheel_offset_z}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${prefix}chassis">
|
<link name="${prefix}chassis">
|
||||||
@ -200,7 +163,7 @@
|
|||||||
<joint name="${prefix}laser_joint" type="fixed">
|
<joint name="${prefix}laser_joint" type="fixed">
|
||||||
<parent link="${prefix}chassis"/>
|
<parent link="${prefix}chassis"/>
|
||||||
<child link="${prefix}laser_frame"/>
|
<child link="${prefix}laser_frame"/>
|
||||||
<origin xyz="${chassis_length/2 - 0.15285} 0 ${chassis_height/2 + 0.030}" rpy="0 0 ${pi}"/>
|
<origin xyz="-0.07 0 10" rpy="0 0 ${pi}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${prefix}laser_frame">
|
<link name="${prefix}laser_frame">
|
||||||
@ -248,7 +211,6 @@
|
|||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<!-- Camera Joint -->
|
<!-- Camera Joint -->
|
||||||
<joint name="${prefix}camera_joint" type="fixed">
|
<joint name="${prefix}camera_joint" type="fixed">
|
||||||
<origin xyz="${chassis_length / 2 - chassis_offset} 0 0" rpy="0 0 ${PI}" />
|
<origin xyz="${chassis_length / 2 - chassis_offset} 0 0" rpy="0 0 ${PI}" />
|
||||||
|
Loading…
Reference in New Issue
Block a user