Skip to content

Commit dd21113

Browse files
committed
Add Seyond description with lower-than-reality resolution & correct FoV for simulation. Fix math for calculating the number of samples
1 parent 70f08ed commit dd21113

File tree

2 files changed

+20
-3
lines changed

2 files changed

+20
-3
lines changed

clearpath_generator_common/clearpath_generator_common/description/sensors.py

+18-1
Original file line numberDiff line numberDiff line change
@@ -208,6 +208,23 @@ def __init__(self, sensor: OusterOS1) -> None:
208208
self.CAP_TYPE: sensor.cap_type,
209209
})
210210

211+
class SeyondLidarDescription(Lidar3dDescription):
212+
213+
def __init__(self, sensor: BaseLidar3D) -> None:
214+
super().__init__(sensor)
215+
216+
self.parameters.update({
217+
self.ANGULAR_RESOLUTION_H: 0.01,
218+
self.ANGULAR_RESOLUTION_V: 0.01,
219+
self.MINIMUM_ANGLE_H: -1.0471975511965976,
220+
self.MAXIMUM_ANGLE_H: 1.0471975511965976,
221+
self.MINIMUM_ANGLE_V: -0.6108652381980153,
222+
self.MAXIMUM_ANGLE_V: 0.6108652381980153,
223+
self.MINIMUM_RANGE: 0.1,
224+
self.MAXIMUM_RANGE: 150.0,
225+
self.UPDATE_RATE: 20 # TODO: link to clearpath_config property
226+
})
227+
211228
class ImuDescription(BaseDescription):
212229
UPDATE_RATE = 'update_rate'
213230

@@ -280,7 +297,7 @@ def __init__(self, sensor: StereolabsZed) -> None:
280297
AxisCamera.SENSOR_MODEL: AxisCameraDescription,
281298
Microstrain.SENSOR_MODEL: ImuDescription,
282299
OusterOS1.SENSOR_MODEL: OusterOS1Description,
283-
SeyondLidar.SENSOR_MODEL: Lidar3dDescription,
300+
SeyondLidar.SENSOR_MODEL: SeyondLidarDescription,
284301
VelodyneLidar.SENSOR_MODEL: Lidar3dDescription,
285302
CHRoboticsUM6.SENSOR_MODEL: ImuDescription,
286303
RedshiftUM7.SENSOR_MODEL: ImuDescription,

clearpath_sensors_description/urdf/seyond_lidar.urdf.xacro

+2-2
Original file line numberDiff line numberDiff line change
@@ -55,8 +55,8 @@
5555
<origin xyz="0 0 0.042" rpy="0 0 0" />
5656
</joint>
5757

58-
<xacro:property name="samples_h" value="${round((max_ang_h - min_ang_h) * 180 / (ang_res_h * pi))}"/>
59-
<xacro:property name="samples_v" value="${round((max_ang_v - min_ang_v) * 180 / (ang_res_v * pi))}"/>
58+
<xacro:property name="samples_h" value="${round((max_ang_h - min_ang_h) / ang_res_h)}"/>
59+
<xacro:property name="samples_v" value="${round((max_ang_v - min_ang_v) / ang_res_v)}"/>
6060
<gazebo reference="${name}_laser">
6161
<sensor name="${name}" type="gpu_lidar">
6262
<update_rate>${update_rate}</update_rate>

0 commit comments

Comments
 (0)