Skip to content

Commit cbdebbd

Browse files
authored
Feature/monitor default sensors (#240)
* Monitor default platform IMUs * Monitor default platform GPS
1 parent 1ed6eb2 commit cbdebbd

File tree

1 file changed

+44
-4
lines changed
  • clearpath_generator_common/clearpath_generator_common/param

1 file changed

+44
-4
lines changed

clearpath_generator_common/clearpath_generator_common/param/platform.py

Lines changed: 44 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
from clearpath_config.common.utils.dictionary import merge_dict, replace_dict_items
3939
from clearpath_config.platform.battery import BatteryConfig
4040
from clearpath_config.sensors.types.cameras import BaseCamera, IntelRealsense
41-
from clearpath_config.sensors.types.gps import BaseGPS
41+
from clearpath_config.sensors.types.gps import BaseGPS, NMEA
4242
from clearpath_config.sensors.types.imu import BaseIMU, PhidgetsSpatial
4343
from clearpath_config.sensors.types.lidars_2d import BaseLidar2D
4444
from clearpath_config.sensors.types.lidars_3d import BaseLidar3D
@@ -224,8 +224,10 @@ def __init__(self,
224224
def generate_parameters(self, use_sim_time: bool = False) -> None:
225225
super().generate_parameters(use_sim_time)
226226

227+
platform_model = self.clearpath_config.get_platform_model()
228+
227229
# Add MCU diagnostic category for all platforms except A200
228-
if self.clearpath_config.get_platform_model() != Platform.A200:
230+
if platform_model != Platform.A200:
229231
self.param_file.update({
230232
self.DIAGNOSTIC_AGGREGATOR_NODE: {
231233
'platform': {
@@ -245,7 +247,7 @@ def generate_parameters(self, use_sim_time: bool = False) -> None:
245247
})
246248

247249
# Add Lighting for every platform except A200 and J100
248-
if self.clearpath_config.get_platform_model() not in (Platform.A200, Platform.J100):
250+
if platform_model not in (Platform.A200, Platform.J100):
249251
self.param_file.update({
250252
self.DIAGNOSTIC_AGGREGATOR_NODE: {
251253
'platform': {
@@ -264,7 +266,7 @@ def generate_parameters(self, use_sim_time: bool = False) -> None:
264266
})
265267

266268
# Add cooling for A300 only for now
267-
if self.clearpath_config.get_platform_model() == Platform.A300:
269+
if platform_model == Platform.A300:
268270
self.param_file.update({
269271
self.DIAGNOSTIC_AGGREGATOR_NODE: {
270272
'platform': {
@@ -316,6 +318,20 @@ def generate_parameters(self, use_sim_time: bool = False) -> None:
316318

317319
sensor_analyzers = {}
318320

321+
if platform_model not in (Platform.A300, Platform.A200):
322+
sensor_analyzers['imu'] = {
323+
'type': 'diagnostic_aggregator/GenericAnalyzer',
324+
'path': 'IMU',
325+
'contains': ['imu']
326+
}
327+
328+
if platform_model == Platform.J100:
329+
sensor_analyzers['gps'] = {
330+
'type': 'diagnostic_aggregator/GenericAnalyzer',
331+
'path': 'GPS',
332+
'contains': ['gps']
333+
}
334+
319335
# List all topics to be monitored from each launched sensor
320336
for sensor in self.clearpath_config.sensors.get_all_sensors():
321337

@@ -457,6 +473,30 @@ def generate_parameters(self, use_sim_time: bool = False) -> None:
457473
}
458474
})
459475

476+
if platform_model not in (Platform.A300, Platform.A200):
477+
self.param_file.update({
478+
self.DIAGNOSTIC_UPDATER_NODE: {
479+
'topics': {
480+
'sensors/imu_0/data': {
481+
'type': BaseIMU.TOPICS.TYPE[BaseIMU.TOPICS.DATA],
482+
'rate': 50.0
483+
}
484+
}
485+
}
486+
})
487+
488+
if platform_model == Platform.J100:
489+
self.param_file.update({
490+
self.DIAGNOSTIC_UPDATER_NODE: {
491+
'topics': {
492+
'sensors/gps_0/fix': {
493+
'type': NMEA.TOPICS.TYPE[NMEA.TOPICS.FIX],
494+
'rate': 10.0
495+
}
496+
}
497+
}
498+
})
499+
460500
# List all topics to be monitored from each launched sensor
461501
for sensor in self.clearpath_config.sensors.get_all_sensors():
462502

0 commit comments

Comments
 (0)