mirror of
https://github.com/bjoernellens1/cps_loki_description.git
synced 2024-11-22 07:33:48 +00:00
update
This commit is contained in:
parent
fbd28c02cb
commit
951ac2ab9e
@ -22,6 +22,7 @@
|
|||||||
<xacro:property name="caster_wheel_mass" value="0.01"/>
|
<xacro:property name="caster_wheel_mass" value="0.01"/>
|
||||||
<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"/>
|
||||||
|
|
||||||
<!-- Materials -->
|
<!-- Materials -->
|
||||||
<material name="white">
|
<material name="white">
|
||||||
@ -250,7 +251,7 @@
|
|||||||
|
|
||||||
<!-- Camera Joint -->
|
<!-- Camera Joint -->
|
||||||
<joint name="${prefix}camera_joint" type="fixed">
|
<joint name="${prefix}camera_joint" type="fixed">
|
||||||
<origin xyz="${base_length / 2 - base_offset} 0 0" rpy="0 0 ${PI}" />
|
<origin xyz="${chassis_length / 2 - chassis_offset} 0 0" rpy="0 0 ${PI}" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}camera_link" />
|
<child link="${prefix}camera_link" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
|
Loading…
Reference in New Issue
Block a user