-
Notifications
You must be signed in to change notification settings - Fork 4.7k
/
Copy pathclient.py
676 lines (538 loc) · 38.2 KB
/
client.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
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
from __future__ import print_function
from .utils import *
from .types import *
import msgpackrpc #install as admin: pip install msgpack-rpc-python
import numpy as np #pip install numpy
import msgpack
import time
import math
import logging
class VehicleClient:
def __init__(self, ip = "", port = 41451, timeout_value = 3600):
if (ip == ""):
ip = "127.0.0.1"
self.client = msgpackrpc.Client(msgpackrpc.Address(ip, port), timeout = timeout_value, pack_encoding = 'utf-8', unpack_encoding = 'utf-8')
# ----------------------------------- Common vehicle APIs ---------------------------------------------
def reset(self):
self.client.call('reset')
def ping(self):
return self.client.call('ping')
def getClientVersion(self):
return 1 # sync with C++ client
def getServerVersion(self):
return self.client.call('getServerVersion')
def getMinRequiredServerVersion(self):
return 1 # sync with C++ client
def getMinRequiredClientVersion(self):
return self.client.call('getMinRequiredClientVersion')
# basic flight control
def enableApiControl(self, is_enabled, vehicle_name = ''):
return self.client.call('enableApiControl', is_enabled, vehicle_name)
def isApiControlEnabled(self, vehicle_name = ''):
return self.client.call('isApiControlEnabled', vehicle_name)
def armDisarm(self, arm, vehicle_name = ''):
return self.client.call('armDisarm', arm, vehicle_name)
def simPause(self, is_paused):
self.client.call('simPause', is_paused)
def simIsPause(self):
return self.client.call("simIsPaused")
def simContinueForTime(self, seconds):
self.client.call('simContinueForTime', seconds)
def getHomeGeoPoint(self, vehicle_name = ''):
return GeoPoint.from_msgpack(self.client.call('getHomeGeoPoint', vehicle_name))
def confirmConnection(self):
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 simSwapTextures(self, tags, tex_id = 0, component_id = 0, material_id = 0):
return self.client.call("simSwapTextures", tags, tex_id, component_id, material_id)
# time-of-day control
def simSetTimeOfDay(self, is_enabled, start_datetime = "", is_start_datetime_dst = False, celestial_clock_speed = 1, update_interval_secs = 60, move_sun = True):
return self.client.call('simSetTimeOfDay', is_enabled, start_datetime, is_start_datetime_dst, celestial_clock_speed, update_interval_secs, move_sun)
# weather
def simEnableWeather(self, enable):
return self.client.call('simEnableWeather', enable)
def simSetWeatherParameter(self, param, val):
return self.client.call('simSetWeatherParameter', param, val)
# camera control
# simGetImage returns compressed png in array of bytes
# image_type uses one of the ImageType members
def simGetImage(self, camera_name, image_type, vehicle_name = ''):
# todo: in future remove below, it's only for compatibility to pre v1.2
camera_name = str(camera_name)
# because this method returns std::vector<uint8>, msgpack decides to encode it as a string unfortunately.
result = self.client.call('simGetImage', camera_name, image_type, vehicle_name)
if (result == "" or result == "\0"):
return None
return result
# camera control
# simGetImage returns compressed png in array of bytes
# image_type uses one of the ImageType members
def simGetImages(self, requests, vehicle_name = ''):
responses_raw = self.client.call('simGetImages', requests, vehicle_name)
return [ImageResponse.from_msgpack(response_raw) for response_raw in responses_raw]
# gets the static meshes in the unreal scene
def simGetMeshPositionVertexBuffers(self):
responses_raw = self.client.call('simGetMeshPositionVertexBuffers')
return [MeshPositionVertexBuffersResponse.from_msgpack(response_raw) for response_raw in responses_raw]
def simGetCollisionInfo(self, vehicle_name = ''):
return CollisionInfo.from_msgpack(self.client.call('simGetCollisionInfo', vehicle_name))
def simSetVehiclePose(self, pose, ignore_collison, vehicle_name = ''):
self.client.call('simSetVehiclePose', pose, ignore_collison, vehicle_name)
def simGetVehiclePose(self, vehicle_name = ''):
pose = self.client.call('simGetVehiclePose', vehicle_name)
return Pose.from_msgpack(pose)
def simSetTraceLine(self, color_rgba, thickness=1.0, vehicle_name = ''):
self.client.call('simSetTraceLine', color_rgba, thickness, vehicle_name)
def simGetObjectPose(self, object_name):
pose = self.client.call('simGetObjectPose', object_name)
return Pose.from_msgpack(pose)
def simSetObjectPose(self, object_name, pose, teleport = True):
return self.client.call('simSetObjectPose', object_name, pose, teleport)
def simListSceneObjects(self, name_regex = '.*'):
return self.client.call('simListSceneObjects', name_regex)
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)
def simPrintLogMessage(self, message, message_param = "", severity = 0):
return self.client.call('simPrintLogMessage', message, message_param, severity)
def simGetCameraInfo(self, camera_name, vehicle_name = ''):
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name))
def simSetCameraOrientation(self, camera_name, orientation, vehicle_name = ''):
"""
- Control the orientation of a selected camera
Args:
camera_name (str): Name of the camera to be controlled
orientation (airsim.Quaternion()): Quaternion representing the desired orientation of the camera
vehicle_name (str, optional): Name of vehicle which the camera corresponds to
"""
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
self.client.call('simSetCameraOrientation', str(camera_name), orientation, vehicle_name)
def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = ''):
"""
- Control the field of view of a selected camera
Args:
camera_name (str): Name of the camera to be controlled
fov_degrees (float): Value of field of view in degrees
vehicle_name (str, optional): Name of vehicle which the camera corresponds to
"""
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
return self.client.call('simSetCameraFov', str(camera_name), fov_degrees, vehicle_name)
def simGetGroundTruthKinematics(self, vehicle_name = ''):
kinematics_state = self.client.call('simGetGroundTruthKinematics', vehicle_name)
return KinematicsState.from_msgpack(kinematics_state)
simGetGroundTruthKinematics.__annotations__ = {'return': KinematicsState}
def simGetGroundTruthEnvironment(self, vehicle_name = ''):
env_state = self.client.call('simGetGroundTruthEnvironment', vehicle_name)
return EnvironmentState.from_msgpack(env_state)
simGetGroundTruthEnvironment.__annotations__ = {'return': EnvironmentState}
# sensor APIs
def getImuData(self, imu_name = '', vehicle_name = ''):
return ImuData.from_msgpack(self.client.call('getImuData', imu_name, vehicle_name))
def getBarometerData(self, barometer_name = '', vehicle_name = ''):
return BarometerData.from_msgpack(self.client.call('getBarometerData', barometer_name, vehicle_name))
def getMagnetometerData(self, magnetometer_name = '', vehicle_name = ''):
return MagnetometerData.from_msgpack(self.client.call('getMagnetometerData', magnetometer_name, vehicle_name))
def getGpsData(self, gps_name = '', vehicle_name = ''):
return GpsData.from_msgpack(self.client.call('getGpsData', gps_name, vehicle_name))
def getDistanceSensorData(self, distance_sensor_name = '', vehicle_name = ''):
return DistanceSensorData.from_msgpack(self.client.call('getDistanceSensorData', distance_sensor_name, vehicle_name))
def getLidarData(self, lidar_name = '', vehicle_name = ''):
return LidarData.from_msgpack(self.client.call('getLidarData', lidar_name, vehicle_name))
def simGetLidarSegmentation(self, lidar_name = '', vehicle_name = ''):
return self.client.call('simGetLidarSegmentation', lidar_name, vehicle_name)
# Plotting APIs
def simFlushPersistentMarkers(self):
"""
Clear any persistent markers - those plotted with setting is_persistent=True in the APIs below
"""
self.client.call('simFlushPersistentMarkers')
def simPlotPoints(self, points, color_rgba=[1.0, 0.0, 0.0, 1.0], size = 10.0, duration = -1.0, is_persistent = False):
"""
Plot a list of 3D points in World NED frame
Args:
points (list[Vector3r]): List of Vector3r objects
color_rgba (list, optional): desired RGBA values from 0.0 to 1.0
size (float, optional): Size of plotted point
duration (float, optional): Duration (seconds) to plot for
is_persistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
"""
self.client.call('simPlotPoints', points, color_rgba, size, duration, is_persistent)
def simPlotLineStrip(self, points, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness = 5.0, duration = -1.0, is_persistent = False):
"""
Plots a line strip in World NED frame, defined from points[0] to points[1], points[1] to points[2], ... , points[n-2] to points[n-1]
Args:
points (list[Vector3r]): List of 3D locations of line start and end points, specified as Vector3r objects
color_rgba (list, optional): desired RGBA values from 0.0 to 1.0
thickness (float, optional): Thickness of line
duration (float, optional): Duration (seconds) to plot for
is_persistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
"""
self.client.call('simPlotLineStrip', points, color_rgba, thickness, duration, is_persistent)
def simPlotLineList(self, points, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness = 5.0, duration = -1.0, is_persistent = False):
"""
Plots a line strip in World NED frame, defined from points[0] to points[1], points[2] to points[3], ... , points[n-2] to points[n-1]
Args:
points (list[Vector3r]): List of 3D locations of line start and end points, specified as Vector3r objects. Must be even
color_rgba (list, optional): desired RGBA values from 0.0 to 1.0
thickness (float, optional): Thickness of line
duration (float, optional): Duration (seconds) to plot for
is_persistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
"""
self.client.call('simPlotLineList', points, color_rgba, thickness, duration, is_persistent)
def simPlotArrows(self, points_start, points_end, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness = 5.0, arrow_size = 2.0, duration = -1.0, is_persistent = False):
"""
Plots a list of arrows in World NED frame, defined from points_start[0] to points_end[0], points_start[1] to points_end[1], ... , points_start[n-1] to points_end[n-1]
Args:
points_start (list[Vector3r]): List of 3D start positions of arrow start positions, specified as Vector3r objects
points_end (list[Vector3r]): List of 3D end positions of arrow start positions, specified as Vector3r objects
color_rgba (list, optional): desired RGBA values from 0.0 to 1.0
thickness (float, optional): Thickness of line
arrow_size (float, optional): Size of arrow head
duration (float, optional): Duration (seconds) to plot for
is_persistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
"""
self.client.call('simPlotArrows', points_start, points_end, color_rgba, thickness, arrow_size, duration, is_persistent)
def simPlotStrings(self, strings, positions, scale = 5, color_rgba=[1.0, 0.0, 0.0, 1.0], duration = -1.0):
"""
Plots a list of strings at desired positions in World NED frame.
Args:
strings (list[String], optional): List of strings to plot
positions (list[Vector3r]): List of positions where the strings should be plotted. Should be in one-to-one correspondence with the strings' list
scale (float, optional): Font scale of transform name
color_rgba (list, optional): desired RGBA values from 0.0 to 1.0
duration (float, optional): Duration (seconds) to plot for
"""
self.client.call('simPlotStrings', strings, positions, scale, color_rgba, duration)
def simPlotTransforms(self, poses, scale = 5.0, thickness = 5.0, duration = -1.0, is_persistent = False):
"""
Plots a list of transforms in World NED frame.
Args:
poses (list[Pose]): List of Pose objects representing the transforms to plot
scale (float, optional): Length of transforms' axes
thickness (float, optional): Thickness of transforms' axes
duration (float, optional): Duration (seconds) to plot for
is_persistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
"""
self.client.call('simPlotTransforms', poses, scale, thickness, duration, is_persistent)
def simPlotTransformsWithNames(self, poses, names, tf_scale = 5.0, tf_thickness = 5.0, text_scale = 10.0, text_color_rgba = [1.0, 0.0, 0.0, 1.0], duration = -1.0):
"""
Plots a list of transforms with their names in World NED frame.
Args:
poses (list[Pose]): List of Pose objects representing the transforms to plot
names (list[string]): List of strings with one-to-one correspondence to list of poses
tf_scale (float, optional): Length of transforms' axes
tf_thickness (float, optional): Thickness of transforms' axes
text_scale (float, optional): Font scale of transform name
text_color_rgba (list, optional): desired RGBA values from 0.0 to 1.0 for the transform name
duration (float, optional): Duration (seconds) to plot for
"""
self.client.call('simPlotTransformsWithNames', poses, names, tf_scale, tf_thickness, text_scale, text_color_rgba, duration)
def cancelLastTask(self, vehicle_name = ''):
self.client.call('cancelLastTask', vehicle_name)
def waitOnLastTask(self, timeout_sec = float('nan')):
return self.client.call('waitOnLastTask', timeout_sec)
# ----------------------------------- Multirotor APIs ---------------------------------------------
class MultirotorClient(VehicleClient, object):
def __init__(self, ip = "", port = 41451, timeout_value = 3600):
super(MultirotorClient, self).__init__(ip, port, timeout_value)
def takeoffAsync(self, timeout_sec = 20, vehicle_name = ''):
return self.client.call_async('takeoff', timeout_sec, vehicle_name)
def landAsync(self, timeout_sec = 60, vehicle_name = ''):
return self.client.call_async('land', timeout_sec, vehicle_name)
def goHomeAsync(self, timeout_sec = 3e+38, vehicle_name = ''):
return self.client.call_async('goHome', timeout_sec, vehicle_name)
# APIs for control
def moveByAngleZAsync(self, pitch, roll, z, yaw, duration, vehicle_name = ''):
return self.client.call_async('moveByAngleZ', pitch, roll, z, yaw, duration, vehicle_name)
def moveByAngleThrottleAsync(self, pitch, roll, throttle, yaw_rate, duration, vehicle_name = ''):
return self.client.call_async('moveByAngleThrottle', pitch, roll, throttle, yaw_rate, duration, vehicle_name)
def moveByVelocityAsync(self, vx, vy, vz, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), vehicle_name = ''):
return self.client.call_async('moveByVelocity', vx, vy, vz, duration, drivetrain, yaw_mode, vehicle_name)
def moveByVelocityZAsync(self, vx, vy, z, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), vehicle_name = ''):
return self.client.call_async('moveByVelocityZ', vx, vy, z, duration, drivetrain, yaw_mode, vehicle_name)
def moveOnPathAsync(self, path, velocity, timeout_sec = 3e+38, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(),
lookahead = -1, adaptive_lookahead = 1, vehicle_name = ''):
return self.client.call_async('moveOnPath', path, velocity, timeout_sec, drivetrain, yaw_mode, lookahead, adaptive_lookahead, vehicle_name)
def moveToPositionAsync(self, x, y, z, velocity, timeout_sec = 3e+38, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(),
lookahead = -1, adaptive_lookahead = 1, vehicle_name = ''):
return self.client.call_async('moveToPosition', x, y, z, velocity, timeout_sec, drivetrain, yaw_mode, lookahead, adaptive_lookahead, vehicle_name)
def moveToZAsync(self, z, velocity, timeout_sec = 3e+38, yaw_mode = YawMode(), lookahead = -1, adaptive_lookahead = 1, vehicle_name = ''):
return self.client.call_async('moveToZ', z, velocity, timeout_sec, yaw_mode, lookahead, adaptive_lookahead, vehicle_name)
def moveByManualAsync(self, vx_max, vy_max, z_min, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), vehicle_name = ''):
"""Read current RC state and use it to control the vehicles.
Parameters sets up the constraints on velocity and minimum altitude while flying. If RC state is detected to violate these constraints
then that RC state would be ignored.
:param vx_max: max velocity allowed in x direction
:param vy_max: max velocity allowed in y direction
:param vz_max: max velocity allowed in z direction
:param z_min: min z allowed for vehicle position
:param duration: after this duration vehicle would switch back to non-manual mode
:param drivetrain: when ForwardOnly, vehicle rotates itself so that its front is always facing the direction of travel. If MaxDegreeOfFreedom then it doesn't do that (crab-like movement)
:param yaw_mode: Specifies if vehicle should face at given angle (is_rate=False) or should be rotating around its axis at given rate (is_rate=True)
"""
return self.client.call_async('moveByManual', vx_max, vy_max, z_min, duration, drivetrain, yaw_mode, vehicle_name)
def rotateToYawAsync(self, yaw, timeout_sec = 3e+38, margin = 5, vehicle_name = ''):
return self.client.call_async('rotateToYaw', yaw, timeout_sec, margin, vehicle_name)
def rotateByYawRateAsync(self, yaw_rate, duration, vehicle_name = ''):
return self.client.call_async('rotateByYawRate', yaw_rate, duration, vehicle_name)
def hoverAsync(self, vehicle_name = ''):
return self.client.call_async('hover', vehicle_name)
def moveByRC(self, rcdata = RCData(), vehicle_name = ''):
return self.client.call('moveByRC', rcdata, vehicle_name)
# low-level control API
def moveByMotorPWMsAsync(self, front_right_pwm, rear_left_pwm, front_left_pwm, rear_right_pwm, duration, vehicle_name = ''):
"""
- Directly control the motors using PWM values
Args:
front_right_pwm (float): PWM value for the front right motor (between 0.0 to 1.0)
rear_left_pwm (float): PWM value for the rear left motor (between 0.0 to 1.0)
front_left_pwm (float): PWM value for the front left motor (between 0.0 to 1.0)
rear_right_pwm (float): PWM value for the rear right motor (between 0.0 to 1.0)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByMotorPWMs', front_right_pwm, rear_left_pwm, front_left_pwm, rear_right_pwm, duration, vehicle_name)
def moveByRollPitchYawZAsync(self, roll, pitch, yaw, z, duration, vehicle_name = ''):
"""
- z is given in local NED frame of the vehicle.
- Roll angle, pitch angle, and yaw angle set points are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll (float): Desired roll angle, in radians.
pitch (float): Desired pitch angle, in radians.
yaw (float): Desired yaw angle, in radians.
z (float): Desired Z value (in local NED frame of the vehicle)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByRollPitchYawZ', roll, -pitch, -yaw, z, duration, vehicle_name)
def moveByRollPitchYawThrottleAsync(self, roll, pitch, yaw, throttle, duration, vehicle_name = ''):
"""
- Desired throttle is between 0.0 to 1.0
- Roll angle, pitch angle, and yaw angle are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll (float): Desired roll angle, in radians.
pitch (float): Desired pitch angle, in radians.
yaw (float): Desired yaw angle, in radians.
throttle (float): Desired throttle (between 0.0 to 1.0)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByRollPitchYawThrottle', roll, -pitch, -yaw, throttle, duration, vehicle_name)
def moveByRollPitchYawrateThrottleAsync(self, roll, pitch, yaw_rate, throttle, duration, vehicle_name = ''):
"""
- Desired throttle is between 0.0 to 1.0
- Roll angle, pitch angle, and yaw rate set points are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll (float): Desired roll angle, in radians.
pitch (float): Desired pitch angle, in radians.
yaw_rate (float): Desired yaw rate, in radian per second.
throttle (float): Desired throttle (between 0.0 to 1.0)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByRollPitchYawrateThrottle', roll, -pitch, -yaw_rate, throttle, duration, vehicle_name)
def moveByRollPitchYawrateZAsync(self, roll, pitch, yaw_rate, z, duration, vehicle_name = ''):
"""
- z is given in local NED frame of the vehicle.
- Roll angle, pitch angle, and yaw rate set points are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll (float): Desired roll angle, in radians.
pitch (float): Desired pitch angle, in radians.
yaw_rate (float): Desired yaw rate, in radian per second.
z (float): Desired Z value (in local NED frame of the vehicle)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByRollPitchYawrateZ', roll, -pitch, -yaw_rate, z, duration, vehicle_name)
def moveByAngleRatesZAsync(self, roll_rate, pitch_rate, yaw_rate, z, duration, vehicle_name = ''):
"""
- z is given in local NED frame of the vehicle.
- Roll rate, pitch rate, and yaw rate set points are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll_rate (float): Desired roll rate, in radians / second
pitch_rate (float): Desired pitch rate, in radians / second
yaw_rate (float): Desired yaw rate, in radians / second
z (float): Desired Z value (in local NED frame of the vehicle)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByAngleRatesZ', roll_rate, -pitch_rate, -yaw_rate, z, duration, vehicle_name)
def moveByAngleRatesThrottleAsync(self, roll_rate, pitch_rate, yaw_rate, throttle, duration, vehicle_name = ''):
"""
- Desired throttle is between 0.0 to 1.0
- Roll rate, pitch rate, and yaw rate set points are given in **radians**, in the body frame.
- The body frame follows the Front Left Up (FLU) convention, and right-handedness.
- Frame Convention:
- X axis is along the **Front** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **roll** angle.
| Hence, rolling with a positive angle is equivalent to translating in the **right** direction, w.r.t. our FLU body frame.
- Y axis is along the **Left** direction of the quadrotor.
| Clockwise rotation about this axis defines a positive **pitch** angle.
| Hence, pitching with a positive angle is equivalent to translating in the **front** direction, w.r.t. our FLU body frame.
- Z axis is along the **Up** direction.
| Clockwise rotation about this axis defines a positive **yaw** angle.
| Hence, yawing with a positive angle is equivalent to rotated towards the **left** direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Args:
roll_rate (float): Desired roll rate, in radians / second
pitch_rate (float): Desired pitch rate, in radians / second
yaw_rate (float): Desired yaw rate, in radians / second
throttle (float): Desired throttle (between 0.0 to 1.0)
duration (float): Desired amount of time (seconds), to send this command for
vehicle_name (str, optional): Name of the multirotor to send this command to
Returns:
msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
"""
return self.client.call_async('moveByAngleRatesThrottle', roll_rate, -pitch_rate, -yaw_rate, throttle, duration, vehicle_name)
def setAngleRateControllerGains(self, angle_rate_gains=AngleRateControllerGains(), vehicle_name = ''):
"""
- Modifying these gains will have an affect on *ALL* move*() APIs.
This is because any velocity setpoint is converted to an angle level setpoint which is tracked with an angle level controllers.
That angle level setpoint is itself tracked with and angle rate controller.
- This function should only be called if the default angle rate control PID gains need to be modified.
Args:
angle_rate_gains (AngleRateControllerGains):
- Correspond to the roll, pitch, yaw axes, defined in the body frame.
- Pass AngleRateControllerGains() to reset gains to default recommended values.
vehicle_name (str, optional): Name of the multirotor to send this command to
"""
self.client.call('setAngleRateControllerGains', *(angle_rate_gains.to_lists()+(vehicle_name,)))
def setAngleLevelControllerGains(self, angle_level_gains=AngleLevelControllerGains(), vehicle_name = ''):
"""
- Sets angle level controller gains (used by any API setting angle references - for ex: moveByRollPitchYawZAsync(), moveByRollPitchYawThrottleAsync(), etc)
- Modifying these gains will also affect the behaviour of moveByVelocityAsync() API.
This is because the AirSim flight controller will track velocity setpoints by converting them to angle set points.
- This function should only be called if the default angle level control PID gains need to be modified.
- Passing AngleLevelControllerGains() sets gains to default airsim values.
Args:
angle_level_gains (AngleLevelControllerGains):
- Correspond to the roll, pitch, yaw axes, defined in the body frame.
- Pass AngleLevelControllerGains() to reset gains to default recommended values.
vehicle_name (str, optional): Name of the multirotor to send this command to
"""
self.client.call('setAngleLevelControllerGains', *(angle_level_gains.to_lists()+(vehicle_name,)))
def setVelocityControllerGains(self, velocity_gains=VelocityControllerGains(), vehicle_name = ''):
"""
- Sets velocity controller gains for moveByVelocityAsync().
- This function should only be called if the default velocity control PID gains need to be modified.
- Passing VelocityControllerGains() sets gains to default airsim values.
Args:
velocity_gains (VelocityControllerGains):
- Correspond to the world X, Y, Z axes.
- Pass VelocityControllerGains() to reset gains to default recommended values.
- Modifying velocity controller gains will have an affect on the behaviour of moveOnSplineAsync() and moveOnSplineVelConstraintsAsync(), as they both use velocity control to track the trajectory.
vehicle_name (str, optional): Name of the multirotor to send this command to
"""
self.client.call('setVelocityControllerGains', *(velocity_gains.to_lists()+(vehicle_name,)))
def setPositionControllerGains(self, position_gains=PositionControllerGains(), vehicle_name = ''):
"""
Sets position controller gains for moveByPositionAsync.
This function should only be called if the default position control PID gains need to be modified.
Args:
position_gains (PositionControllerGains):
- Correspond to the X, Y, Z axes.
- Pass PositionControllerGains() to reset gains to default recommended values.
vehicle_name (str, optional): Name of the multirotor to send this command to
"""
self.client.call('setPositionControllerGains', *(position_gains.to_lists()+(vehicle_name,)))
# query vehicle state
def getMultirotorState(self, vehicle_name = ''):
return MultirotorState.from_msgpack(self.client.call('getMultirotorState', vehicle_name))
getMultirotorState.__annotations__ = {'return': MultirotorState}
# ----------------------------------- Car APIs ---------------------------------------------
class CarClient(VehicleClient, object):
def __init__(self, ip = "", port = 41451, timeout_value = 3600):
super(CarClient, self).__init__(ip, port, timeout_value)
def setCarControls(self, controls, vehicle_name = ''):
self.client.call('setCarControls', controls, vehicle_name)
def getCarState(self, vehicle_name = ''):
state_raw = self.client.call('getCarState', vehicle_name)
return CarState.from_msgpack(state_raw)
def getCarControls(self, vehicle_name=''):
controls_raw = self.client.call('getCarControls', vehicle_name)
return CarControls.from_msgpack(controls_raw)