@@ -80,12 +80,7 @@ class InertialMeasurementUnit():
80
80
81
81
@classmethod
82
82
def assert_model (cls , model : str ) -> None :
83
- assert model in cls .MODEL , (
84
- 'Model ' % s ' must be one of: ' % s '' % (
85
- model ,
86
- cls .MODEL .keys ()
87
- )
88
- )
83
+ assert model in cls .MODEL , f'Model "{ model } " must be one of "{ cls .MODEL .keys ()} "'
89
84
90
85
def __new__ (cls , model : str ) -> BaseIMU :
91
86
cls .assert_model (model )
@@ -107,12 +102,7 @@ class Camera():
107
102
108
103
@classmethod
109
104
def assert_model (cls , model : str ) -> None :
110
- assert model in cls .MODEL , (
111
- 'Model ' % s ' must be one of: ' % s '' % (
112
- model ,
113
- cls .MODEL .keys ()
114
- )
115
- )
105
+ assert model in cls .MODEL , f'Model "{ model } " must be one of "{ cls .MODEL .keys ()} "'
116
106
117
107
def __new__ (cls , model : str ) -> BaseCamera :
118
108
cls .assert_model (model )
@@ -136,12 +126,7 @@ class GlobalPositioningSystem():
136
126
137
127
@classmethod
138
128
def assert_model (cls , model : str ) -> None :
139
- assert model in cls .MODEL , (
140
- 'Model ' % s ' must be one of: ' % s '' % (
141
- model ,
142
- cls .MODEL .keys ()
143
- )
144
- )
129
+ assert model in cls .MODEL , f'Model "{ model } " must be one of "{ cls .MODEL .keys ()} "'
145
130
146
131
def __new__ (cls , model : str ) -> BaseGPS :
147
132
cls .assert_model (model )
@@ -159,12 +144,7 @@ class Lidar2D():
159
144
160
145
@classmethod
161
146
def assert_model (cls , model : str ) -> None :
162
- assert model in cls .MODEL , (
163
- 'Model ' % s ' must be one of: ' % s '' % (
164
- model ,
165
- cls .MODEL .keys ()
166
- )
167
- )
147
+ assert model in cls .MODEL , f'Model "{ model } " must be one of "{ cls .MODEL .keys ()} "'
168
148
169
149
def __new__ (cls , model : str ) -> BaseLidar2D :
170
150
cls .assert_model (model )
@@ -180,12 +160,7 @@ class Lidar3D():
180
160
181
161
@classmethod
182
162
def assert_model (cls , model : str ) -> None :
183
- assert model in cls .MODEL , (
184
- 'Model ' % s ' must be one of: ' % s '' % (
185
- model ,
186
- cls .MODEL .keys ()
187
- )
188
- )
163
+ assert model in cls .MODEL , f'Model "{ model } " must be one of "{ cls .MODEL .keys ()} "'
189
164
190
165
def __new__ (cls , model : str ) -> BaseLidar3D :
191
166
cls .assert_model (model )
@@ -209,12 +184,7 @@ class Sensor():
209
184
210
185
@classmethod
211
186
def assert_type (cls , _type : str ) -> None :
212
- assert _type in cls .TYPE , (
213
- 'Sensor type ' % s ' must be one of: ' % s '' % (
214
- _type ,
215
- cls .TYPE .keys ()
216
- )
217
- )
187
+ assert _type in cls .TYPE , f'Sensor type "{ _type } " must be one of "{ cls .TYPE .keys ()} "'
218
188
219
189
def __new__ (cls , _type : str , _model : str ) -> BaseSensor :
220
190
cls .assert_type (_type )
@@ -319,11 +289,11 @@ def camera(self) -> OrderedListConfig:
319
289
@camera .setter
320
290
def camera (self , value : List [dict ]) -> None :
321
291
assert isinstance (value , list ), (
322
- 'Sensors must be list of ' dict ' ' )
292
+ 'Sensors must be list of " dict" ' )
323
293
assert all ([isinstance (d , dict ) for d in value ]), (
324
- 'Sensors must be list of ' dict ' ' )
294
+ 'Sensors must be list of " dict" ' )
325
295
assert all (['model' in d for d in value ]), (
326
- 'Sensor ' dict ' must have ' model ' key' )
296
+ 'Sensor " dict" must have " model" key' )
327
297
sensor_list = []
328
298
for d in value :
329
299
sensor = Camera (d ['model' ])
@@ -342,11 +312,11 @@ def gps(self) -> OrderedListConfig:
342
312
@gps .setter
343
313
def gps (self , value : List [dict ]) -> None :
344
314
assert isinstance (value , list ), (
345
- 'Sensors must be list of ' dict ' ' )
315
+ 'Sensors must be list of " dict" ' )
346
316
assert all ([isinstance (d , dict ) for d in value ]), (
347
- 'Sensors must be list of ' dict ' ' )
317
+ 'Sensors must be list of " dict" ' )
348
318
assert all (['model' in d for d in value ]), (
349
- 'Sensor ' dict ' must have ' model ' key' )
319
+ 'Sensor " dict" must have " model" key' )
350
320
sensor_list = []
351
321
for d in value :
352
322
sensor = GlobalPositioningSystem (d ['model' ])
@@ -365,11 +335,11 @@ def imu(self) -> OrderedListConfig:
365
335
@imu .setter
366
336
def imu (self , value : List [dict ]) -> None :
367
337
assert isinstance (value , list ), (
368
- 'Sensors must be list of ' dict ' ' )
338
+ 'Sensors must be list of " dict" ' )
369
339
assert all ([isinstance (d , dict ) for d in value ]), (
370
- 'Sensors must be list of ' dict ' ' )
340
+ 'Sensors must be list of " dict" ' )
371
341
assert all (['model' in d for d in value ]), (
372
- 'Sensor ' dict ' must have ' model ' key' )
342
+ 'Sensor " dict" must have " model" key' )
373
343
sensor_list = []
374
344
for d in value :
375
345
sensor = InertialMeasurementUnit (d ['model' ])
@@ -388,11 +358,11 @@ def lidar2d(self) -> OrderedListConfig:
388
358
@lidar2d .setter
389
359
def lidar2d (self , value : List [dict ]) -> None :
390
360
assert isinstance (value , list ), (
391
- 'Sensors must be list of ' dict ' ' )
361
+ 'Sensors must be list of " dict" ' )
392
362
assert all ([isinstance (d , dict ) for d in value ]), (
393
- 'Sensors must be list of ' dict ' ' )
363
+ 'Sensors must be list of " dict" ' )
394
364
assert all (['model' in d for d in value ]), (
395
- 'Sensor ' dict ' must have ' model ' key' )
365
+ 'Sensor " dict" must have " model" key' )
396
366
sensor_list = []
397
367
for d in value :
398
368
sensor = Lidar2D (d ['model' ])
@@ -411,11 +381,11 @@ def lidar3d(self) -> OrderedListConfig:
411
381
@lidar3d .setter
412
382
def lidar3d (self , value : List [dict ]) -> None :
413
383
assert isinstance (value , list ), (
414
- 'Sensors must be list of ' dict ' ' )
384
+ 'Sensors must be list of " dict" ' )
415
385
assert all ([isinstance (d , dict ) for d in value ]), (
416
- 'Sensors must be list of ' dict ' ' )
386
+ 'Sensors must be list of " dict" ' )
417
387
assert all (['model' in d for d in value ]), (
418
- 'Sensor ' dict ' must have ' model ' key' )
388
+ 'Sensor " dict" must have " model" key' )
419
389
sensor_list = []
420
390
for d in value :
421
391
sensor = Lidar3D (d ['model' ])
0 commit comments