Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -133,15 +133,19 @@ def __init__(self, sensor: BaseLidar3D) -> None:
class OusterOS1Description(Lidar3dDescription):
SAMPLES_HORIZONTAL = 'samples_h'
SAMPLES_VERTICAL = 'samples_v'
BASE_TYPE = 'base'
CAP_TYPE = 'cap'

def __init__(self, sensor: BaseLidar3D) -> None:
def __init__(self, sensor: OusterOS1) -> None:
super().__init__(sensor)

del self.parameters[self.ANGULAR_RESOLUTION_H]
del self.parameters[self.ANGULAR_RESOLUTION_V]
self.parameters.update({
self.SAMPLES_HORIZONTAL: 1024,
self.SAMPLES_VERTICAL: 64
self.SAMPLES_VERTICAL: 64,
self.BASE_TYPE: sensor.base_type,
self.CAP_TYPE: sensor.cap_type,
})

class ImuDescription(BaseDescription):
Expand Down
73 changes: 43 additions & 30 deletions clearpath_sensors_description/urdf/ouster_os1.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
name
parent_link
cap:=halo
base:=base
*origin
samples_h:=1024 min_ang_h:=${-pi} max_ang_h:=${pi}
samples_v:=64 min_ang_v:=${-21.2 * pi/180} max_ang_v:=${21.2 * pi/180}
Expand All @@ -32,9 +33,16 @@
<xacro:property name="lidar_height" value="0.05835"/>
<xacro:property name="lidar_diameter" value="0.087"/>

<xacro:property name="base_mass" value="0."/>
<xacro:property name="base_height" value="0.0225"/>
<xacro:property name="base_length" value="0.110"/>
<xacro:if value="${base == 'base'}">
<xacro:property name="base_mass" value="0.0"/>
<xacro:property name="base_height" value="0.0225"/>
<xacro:property name="base_length" value="0.110"/>
</xacro:if>
<xacro:unless value="${base == 'base'}">
<xacro:property name="base_mass" value="0.0"/>
<xacro:property name="base_height" value="0.0"/>
<xacro:property name="base_length" value="0.0"/>
</xacro:unless>

<xacro:property name="fins_mass" value="0.079"/>
<xacro:property name="fins_height" value="0.022"/>
Expand All @@ -46,33 +54,38 @@


<!-- Base Link -->
<link name="${name}_base_link">
<inertial>
<mass value="${base_mass}"/>
<origin xyz="0 0 ${base_height/2}"/>
<xacro:ouster_box_inertia
mass="${base_mass}"
x="${base_length}"
y="${base_length}"
z="${base_height}"
/>
</inertial>
<visual>
<material name="ouster_grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
<origin xyz="0 0 ${base_height}"/>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/ouster/os1_base.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${base_height/2}"/>
<geometry>
<box size="${base_length} ${base_length} ${base_height}"/>
</geometry>
</collision>
</link>
<xacro:if value="${base == 'base'}">
<link name="${name}_base_link">
<inertial>
<mass value="${base_mass}"/>
<origin xyz="0 0 ${base_height/2}"/>
<xacro:ouster_box_inertia
mass="${base_mass}"
x="${base_length}"
y="${base_length}"
z="${base_height}"
/>
</inertial>
<visual>
<material name="ouster_grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
<origin xyz="0 0 ${base_height}"/>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/ouster/os1_base.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${base_height/2}"/>
<geometry>
<box size="${base_length} ${base_length} ${base_height}"/>
</geometry>
</collision>
</link>
</xacro:if>
<xacro:unless value="${base == 'base'}">
<link name="${name}_base_link" />
</xacro:unless>

<!-- Lidar Link -->
<link name="${name}_link">
Expand Down
Loading