-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathAirSimClient.py
653 lines (546 loc) · 23.4 KB
/
AirSimClient.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
from __future__ import print_function
import msgpackrpc #install as admin: pip install msgpack-rpc-python
import numpy as np #pip install numpy
import msgpack
import math
import time
import sys
import os
import inspect
import types
import re
class MsgpackMixin:
def to_msgpack(self, *args, **kwargs):
return self.__dict__ #msgpack.dump(self.to_dict(*args, **kwargs))
@classmethod
def from_msgpack(cls, encoded):
obj = cls()
obj.__dict__ = {k.decode('utf-8'): v for k, v in encoded.items()}
return obj
class AirSimImageType:
Scene = 0
DepthPlanner = 1
DepthPerspective = 2
DepthVis = 3
DisparityNormalized = 4
Segmentation = 5
SurfaceNormals = 6
class DrivetrainType:
MaxDegreeOfFreedom = 0
ForwardOnly = 1
class LandedState:
Landed = 0
Flying = 1
class Vector3r(MsgpackMixin):
x_val = np.float32(0)
y_val = np.float32(0)
z_val = np.float32(0)
def __init__(self, x_val = np.float32(0), y_val = np.float32(0), z_val = np.float32(0)):
self.x_val = x_val
self.y_val = y_val
self.z_val = z_val
class Quaternionr(MsgpackMixin):
w_val = np.float32(0)
x_val = np.float32(0)
y_val = np.float32(0)
z_val = np.float32(0)
def __init__(self, x_val = np.float32(0), y_val = np.float32(0), z_val = np.float32(0), w_val = np.float32(1)):
self.x_val = x_val
self.y_val = y_val
self.z_val = z_val
self.w_val = w_val
class Pose(MsgpackMixin):
position = Vector3r()
orientation = Quaternionr()
def __init__(self, position_val, orientation_val):
self.position = position_val
self.orientation = orientation_val
class CollisionInfo(MsgpackMixin):
has_collided = False
normal = Vector3r()
impact_point = Vector3r()
position = Vector3r()
penetration_depth = np.float32(0)
time_stamp = np.float32(0)
object_name = ""
object_id = -1
class GeoPoint(MsgpackMixin):
latitude = 0.0
longitude = 0.0
altitude = 0.0
class YawMode(MsgpackMixin):
is_rate = True
yaw_or_rate = 0.0
def __init__(self, is_rate = True, yaw_or_rate = 0.0):
self.is_rate = is_rate
self.yaw_or_rate = yaw_or_rate
class ImageRequest(MsgpackMixin):
camera_id = np.uint8(0)
image_type = AirSimImageType.Scene
pixels_as_float = False
compress = False
def __init__(self, camera_id, image_type, pixels_as_float = False, compress = True):
self.camera_id = camera_id
self.image_type = image_type
self.pixels_as_float = pixels_as_float
self.compress = compress
class ImageResponse(MsgpackMixin):
image_data_uint8 = np.uint8(0)
image_data_float = np.float32(0)
camera_position = Vector3r()
camera_orientation = Quaternionr()
time_stamp = np.uint64(0)
message = ''
pixels_as_float = np.float32(0)
compress = True
width = 0
height = 0
image_type = AirSimImageType.Scene
class CarControls(MsgpackMixin):
throttle = np.float32(0)
steering = np.float32(0)
brake = np.float32(0)
handbrake = False
is_manual_gear = False
manual_gear = 0
gear_immediate = True
def set_throttle(self, throttle_val, forward):
if (forward):
is_manual_gear = False
manual_gear = 0
throttle = abs(throttle_val)
else:
is_manual_gear = False
manual_gear = -1
throttle = - abs(throttle_val)
class CarState(MsgpackMixin):
speed = np.float32(0)
gear = 0
position = Vector3r()
velocity = Vector3r()
orientation = Quaternionr()
class AirSimClientBase:
def __init__(self, ip, port):
self.client = msgpackrpc.Client(msgpackrpc.Address(ip, port), timeout = 3600)
def ping(self):
return self.client.call('ping')
def reset(self):
self.client.call('reset')
# def getMinRequiredServerVersion(self):
# return 1 # sync with C++ client
#
# def getMinRequiredClientVersion(self):
# return self.client.call('getMinRequiredClientVersion')
# def getClientVersion(self):
# return 1 # sync with C++ client
# def getServerVersion(self):
# return self.client.call('getServerVersion')
# def confirmConnection(self):
# """
# Checks state of connection every 1 sec and reports it in Console so user can see the progress for connection.
# """
# if self.ping():
# print("Connected!")
# else:
# print("Ping returned false!")
# server_ver = self.getServerVersion()
# client_ver = self.getClientVersion()
# server_min_ver = self.getMinRequiredServerVersion()
# client_min_ver = self.getMinRequiredClientVersion()
#
# ver_info = "Client Ver:" + str(client_ver) + " (Min Req: " + str(client_min_ver) + \
# "), Server Ver:" + str(server_ver) + " (Min Req: " + str(server_min_ver) + ")"
#
# if server_ver < server_min_ver:
# print(ver_info, file=sys.stderr)
# print("AirSim server is of older version and not supported by this client. Please upgrade!")
# elif client_ver < client_min_ver:
# print(ver_info, file=sys.stderr)
# print("AirSim client is of older version and not supported by this server. Please upgrade!")
# else:
# print(ver_info)
# print('')
def confirmConnection(self):
print('Waiting for connection: ', end='')
home = self.getHomeGeoPoint()
while ((home.latitude == 0 and home.longitude == 0 and home.altitude == 0) or
math.isnan(home.latitude) or math.isnan(home.longitude) or math.isnan(home.altitude)):
time.sleep(1)
home = self.getHomeGeoPoint()
print('X', end='')
print('')
def getHomeGeoPoint(self):
return GeoPoint.from_msgpack(self.client.call('getHomeGeoPoint'))
# basic flight control
# def enableApiControl(self, is_enabled, vehicle_name = ''):
# """
# Enables or disables API control for vehicle corresponding to vehicle_name
# Args:
# is_enabled (bool): True to enable, False to disable API control
# vehicle_name (str, optional): Name of the vehicle to send this command to
# """
# self.client.call('enableApiControl', is_enabled, vehicle_name)
#
# def isApiControlEnabled(self, vehicle_name = ''):
# """
# Returns true if API control is established.
# If false (which is default) then API calls would be ignored. After a successful call to `enableApiControl`, `isApiControlEnabled` should return true.
# Args:
# vehicle_name (str, optional): Name of the vehicle
# Returns:
# bool: If API control is enabled
# """
# return self.client.call('isApiControlEnabled', vehicle_name)
def enableApiControl(self, is_enabled):
return self.client.call('enableApiControl', is_enabled)
def isApiControlEnabled(self):
return self.client.call('isApiControlEnabled')
def simSetSegmentationObjectID(self, mesh_name, object_id, is_name_regex = False):
return self.client.call('simSetSegmentationObjectID', mesh_name, object_id, is_name_regex)
def simGetSegmentationObjectID(self, mesh_name):
return self.client.call('simGetSegmentationObjectID', mesh_name)
# camera control
# simGetImage returns compressed png in array of bytes
# image_type uses one of the AirSimImageType members
def simGetImages(self, requests, vehicle_name = '', external = False):
"""
Get multiple images
See https://microsoft.github.io/AirSim/image_apis/ for details and examples
Args:
requests (list[ImageRequest]): Images required
vehicle_name (str, optional): Name of vehicle associated with the camera
external (bool, optional): Whether the camera is an External Camera
Returns:
list[ImageResponse]:
"""
responses_raw = self.client.call('simGetImages', requests, vehicle_name, external)
return [ImageResponse.from_msgpack(response_raw) for response_raw in responses_raw]
# camera control
# simGetImage returns compressed png in array of bytes
# image_type uses one of the AirSimImageType members
def simGetImages(self, requests):
responses_raw = self.client.call('simGetImages', requests)
return [ImageResponse.from_msgpack(response_raw) for response_raw in responses_raw]
def getCollisionInfo(self):
return CollisionInfo.from_msgpack(self.client.call('getCollisionInfo'))
@staticmethod
def stringToUint8Array(bstr):
return np.fromstring(bstr, np.uint8)
@staticmethod
def stringToFloatArray(bstr):
return np.fromstring(bstr, np.float32)
@staticmethod
def listTo2DFloatArray(flst, width, height):
return np.reshape(np.asarray(flst, np.float32), (height, width))
@staticmethod
def getPfmArray(response):
return AirSimClientBase.listTo2DFloatArray(response.image_data_float, response.width, response.height)
@staticmethod
def get_public_fields(obj):
return [attr for attr in dir(obj)
if not (attr.startswith("_")
or inspect.isbuiltin(attr)
or inspect.isfunction(attr)
or inspect.ismethod(attr))]
@staticmethod
def to_dict(obj):
return dict([attr, getattr(obj, attr)] for attr in AirSimClientBase.get_public_fields(obj))
@staticmethod
def to_str(obj):
return str(AirSimClientBase.to_dict(obj))
@staticmethod
def write_file(filename, bstr):
with open(filename, 'wb') as afile:
afile.write(bstr)
def simSetPose(self, pose, ignore_collison):
self.client.call('simSetPose', pose, ignore_collison)
def simGetPose(self):
return self.client.call('simGetPose')
# helper method for converting getOrientation to roll/pitch/yaw
# https:#en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles
@staticmethod
def toEulerianAngle(q):
z = q.z_val
y = q.y_val
x = q.x_val
w = q.w_val
ysqr = y * y
# roll (x-axis rotation)
t0 = +2.0 * (w*x + y*z)
t1 = +1.0 - 2.0*(x*x + ysqr)
roll = math.atan2(t0, t1)
# pitch (y-axis rotation)
t2 = +2.0 * (w*y - z*x)
if (t2 > 1.0):
t2 = 1
if (t2 < -1.0):
t2 = -1.0
pitch = math.asin(t2)
# yaw (z-axis rotation)
t3 = +2.0 * (w*z + x*y)
t4 = +1.0 - 2.0 * (ysqr + z*z)
yaw = math.atan2(t3, t4)
return (pitch, roll, yaw)
@staticmethod
def toQuaternion(pitch, roll, yaw):
t0 = math.cos(yaw * 0.5)
t1 = math.sin(yaw * 0.5)
t2 = math.cos(roll * 0.5)
t3 = math.sin(roll * 0.5)
t4 = math.cos(pitch * 0.5)
t5 = math.sin(pitch * 0.5)
q = Quaternionr()
q.w_val = t0 * t2 * t4 + t1 * t3 * t5 #w
q.x_val = t0 * t3 * t4 - t1 * t2 * t5 #x
q.y_val = t0 * t2 * t5 + t1 * t3 * t4 #y
q.z_val = t1 * t2 * t4 - t0 * t3 * t5 #z
return q
@staticmethod
def wait_key(message = ''):
''' Wait for a key press on the console and return it. '''
if message != '':
print (message)
result = None
if os.name == 'nt':
import msvcrt
result = msvcrt.getch()
else:
import termios
fd = sys.stdin.fileno()
oldterm = termios.tcgetattr(fd)
newattr = termios.tcgetattr(fd)
newattr[3] = newattr[3] & ~termios.ICANON & ~termios.ECHO
termios.tcsetattr(fd, termios.TCSANOW, newattr)
try:
result = sys.stdin.read(1)
except IOError:
pass
finally:
termios.tcsetattr(fd, termios.TCSAFLUSH, oldterm)
return result
@staticmethod
def read_pfm(file):
""" Read a pfm file """
file = open(file, 'rb')
color = None
width = None
height = None
scale = None
endian = None
header = file.readline().rstrip()
header = str(bytes.decode(header, encoding='utf-8'))
if header == 'PF':
color = True
elif header == 'Pf':
color = False
else:
raise Exception('Not a PFM file.')
temp_str = str(bytes.decode(file.readline(), encoding='utf-8'))
dim_match = re.match(r'^(\d+)\s(\d+)\s$', temp_str)
if dim_match:
width, height = map(int, dim_match.groups())
else:
raise Exception('Malformed PFM header.')
scale = float(file.readline().rstrip())
if scale < 0: # little-endian
endian = '<'
scale = -scale
else:
endian = '>' # big-endian
data = np.fromfile(file, endian + 'f')
shape = (height, width, 3) if color else (height, width)
data = np.reshape(data, shape)
# DEY: I don't know why this was there.
#data = np.flipud(data)
file.close()
return data, scale
@staticmethod
def write_pfm(file, image, scale=1):
""" Write a pfm file """
file = open(file, 'wb')
color = None
if image.dtype.name != 'float32':
raise Exception('Image dtype must be float32.')
image = np.flipud(image)
if len(image.shape) == 3 and image.shape[2] == 3: # color image
color = True
elif len(image.shape) == 2 or len(image.shape) == 3 and image.shape[2] == 1: # greyscale
color = False
else:
raise Exception('Image must have H x W x 3, H x W x 1 or H x W dimensions.')
file.write('PF\n'.encode('utf-8') if color else 'Pf\n'.encode('utf-8'))
temp_str = '%d %d\n' % (image.shape[1], image.shape[0])
file.write(temp_str.encode('utf-8'))
endian = image.dtype.byteorder
if endian == '<' or endian == '=' and sys.byteorder == 'little':
scale = -scale
temp_str = '%f\n' % scale
file.write(temp_str.encode('utf-8'))
image.tofile(file)
@staticmethod
def write_png(filename, image):
""" image must be numpy array H X W X channels
"""
import zlib, struct
buf = image.flatten().tobytes()
width = image.shape[1]
height = image.shape[0]
# reverse the vertical line order and add null bytes at the start
width_byte_4 = width * 4
raw_data = b''.join(b'\x00' + buf[span:span + width_byte_4]
for span in range((height - 1) * width_byte_4, -1, - width_byte_4))
def png_pack(png_tag, data):
chunk_head = png_tag + data
return (struct.pack("!I", len(data)) +
chunk_head +
struct.pack("!I", 0xFFFFFFFF & zlib.crc32(chunk_head)))
png_bytes = b''.join([
b'\x89PNG\r\n\x1a\n',
png_pack(b'IHDR', struct.pack("!2I5B", width, height, 8, 6, 0, 0, 0)),
png_pack(b'IDAT', zlib.compress(raw_data, 9)),
png_pack(b'IEND', b'')])
AirSimClientBase.write_file(filename, png_bytes)
def simSetDetectionFilterRadius(self, camera_name, image_type, radius_cm, vehicle_name = '', external = False):
"""
Set detection radius for all cameras
Args:
camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
image_type (ImageType): Type of image required
radius_cm (int): Radius in [cm]
vehicle_name (str, optional): Vehicle which the camera is associated with
external (bool, optional): Whether the camera is an External Camera
"""
self.client.call('simSetDetectionFilterRadius', camera_name, image_type, radius_cm, vehicle_name, external)
def simAddDetectionFilterMeshName(self, camera_name, image_type, mesh_name, vehicle_name = '', external = False):
"""
Add mesh name to detect in wild card format
For example: simAddDetectionFilterMeshName("Car_*") will detect all instance named "Car_*"
Args:
camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
image_type (ImageType): Type of image required
mesh_name (str): mesh name in wild card format
vehicle_name (str, optional): Vehicle which the camera is associated with
external (bool, optional): Whether the camera is an External Camera
"""
self.client.call('simAddDetectionFilterMeshName', camera_name, image_type, mesh_name, vehicle_name, external)
def simGetDetections(self, camera_name, image_type, vehicle_name = '', external = False):
"""
Get current detections
Args:
camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
image_type (ImageType): Type of image required
vehicle_name (str, optional): Vehicle which the camera is associated with
external (bool, optional): Whether the camera is an External Camera
Returns:
DetectionInfo array
"""
responses_raw = self.client.call('simGetDetections', camera_name, image_type, vehicle_name, external)
return [DetectionInfo.from_msgpack(response_raw) for response_raw in responses_raw]
def simClearDetectionMeshNames(self, camera_name, image_type, vehicle_name = '', external = False):
"""
Clear all mesh names from detection filter
Args:
camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
image_type (ImageType): Type of image required
vehicle_name (str, optional): Vehicle which the camera is associated with
external (bool, optional): Whether the camera is an External Camera
"""
self.client.call('simClearDetectionMeshNames', camera_name, image_type, vehicle_name, external)
# ----------------------------------- Multirotor APIs ---------------------------------------------
class MultirotorClient(AirSimClientBase, object):
def __init__(self, ip = ""):
if (ip == ""):
ip = "127.0.0.1"
super(MultirotorClient, self).__init__(ip, 41451)
def armDisarm(self, arm):
return self.client.call('armDisarm', arm)
def takeoff(self, max_wait_seconds = 15):
return self.client.call('takeoff', max_wait_seconds)
def land(self, max_wait_seconds = 60):
return self.client.call('land', max_wait_seconds)
def goHome(self):
return self.client.call('goHome')
def hover(self):
return self.client.call('hover')
# query vehicle state
def getPosition(self):
return Vector3r.from_msgpack(self.client.call('getPosition'))
def getVelocity(self):
return Vector3r.from_msgpack(self.client.call('getVelocity'))
def getOrientation(self):
return Quaternionr.from_msgpack(self.client.call('getOrientation'))
def getLandedState(self):
return self.client.call('getLandedState')
def getGpsLocation(self):
return GeoPoint.from_msgpack(self.client.call('getGpsLocation'))
def getPitchRollYaw(self):
return self.toEulerianAngle(self.getOrientation())
#def getRCData(self):
# return self.client.call('getRCData')
def timestampNow(self):
return self.client.call('timestampNow')
def isApiControlEnabled(self):
return self.client.call('isApiControlEnabled')
def isSimulationMode(self):
return self.client.call('isSimulationMode')
def getServerDebugInfo(self):
return self.client.call('getServerDebugInfo')
# APIs for control
def moveByAngle(self, pitch, roll, z, yaw, duration):
return self.client.call('moveByAngle', pitch, roll, z, yaw, duration)
def moveByVelocity(self, vx, vy, vz, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode()):
return self.client.call('moveByVelocity', vx, vy, vz, duration, drivetrain, yaw_mode)
def moveByVelocityZ(self, vx, vy, z, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode()):
return self.client.call('moveByVelocityZ', vx, vy, z, duration, drivetrain, yaw_mode)
def moveOnPath(self, path, velocity, max_wait_seconds = 60, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), lookahead = -1, adaptive_lookahead = 1):
return self.client.call('moveOnPath', path, velocity, max_wait_seconds, drivetrain, yaw_mode, lookahead, adaptive_lookahead)
def moveToZ(self, z, velocity, max_wait_seconds = 60, yaw_mode = YawMode(), lookahead = -1, adaptive_lookahead = 1):
return self.client.call('moveToZ', z, velocity, max_wait_seconds, yaw_mode, lookahead, adaptive_lookahead)
def moveToPosition(self, x, y, z, velocity, max_wait_seconds = 60, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), lookahead = -1, adaptive_lookahead = 1):
return self.client.call('moveToPosition', x, y, z, velocity, max_wait_seconds, drivetrain, yaw_mode, lookahead, adaptive_lookahead)
def moveByManual(self, vx_max, vy_max, z_min, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode()):
return self.client.call('moveByManual', vx_max, vy_max, z_min, duration, drivetrain, yaw_mode)
def rotateToYaw(self, yaw, max_wait_seconds = 60, margin = 5):
return self.client.call('rotateToYaw', yaw, max_wait_seconds, margin)
def rotateByYawRate(self, yaw_rate, duration):
return self.client.call('rotateByYawRate', yaw_rate, duration)
# ----------------------------------- Car APIs ---------------------------------------------
class CarClient(AirSimClientBase, object):
def __init__(self, ip = ""):
if (ip == ""):
ip = "127.0.0.1"
super(CarClient, self).__init__(ip, 42451)
# def setCarControls(self, controls, vehicle_name = ''):
# """
# Control the car using throttle, steering, brake, etc.
# Args:
# controls (CarControls): Struct containing control values
# vehicle_name (str, optional): Name of vehicle to be controlled
# """
# self.client.call('setCarControls', controls, vehicle_name)
#
# def getCarState(self, vehicle_name = ''):
# """
# The position inside the returned CarState is in the frame of the vehicle's starting point
# Args:
# vehicle_name (str, optional): Name of vehicle
# Returns:
# CarState:
# """
# state_raw = self.client.call('getCarState', vehicle_name)
# return CarState.from_msgpack(state_raw)
#
# def getCarControls(self, vehicle_name=''):
# """
# Args:
# vehicle_name (str, optional): Name of vehicle
# Returns:
# CarControls:
# """
# controls_raw = self.client.call('getCarControls', vehicle_name)
# return CarControls.from_msgpack(controls_raw)
def setCarControls(self, controls):
self.client.call('setCarControls', controls)
def getCarState(self):
state_raw = self.client.call('getCarState')
return CarState.from_msgpack(state_raw)