2019-11-07 21:31:15 -08:00
|
|
|
import setup_path
|
2018-06-17 04:19:13 -07:00
|
|
|
import airsim
|
|
|
|
|
|
2018-06-15 02:59:05 -07:00
|
|
|
import sys
|
|
|
|
|
import time
|
|
|
|
|
|
2019-12-12 02:43:57 -08:00
|
|
|
print("""This script is designed to fly on the streets of the Neighborhood environment
|
|
|
|
|
and assumes the unreal position of the drone is [160, -1500, 120].""")
|
|
|
|
|
|
2018-06-15 21:27:58 -07:00
|
|
|
client = airsim.MultirotorClient()
|
2018-06-15 02:59:05 -07:00
|
|
|
client.confirmConnection()
|
|
|
|
|
client.enableApiControl(True)
|
|
|
|
|
|
2019-11-07 21:31:15 -08:00
|
|
|
print("arming the drone...")
|
2018-11-29 20:01:22 -08:00
|
|
|
client.armDisarm(True)
|
|
|
|
|
|
2019-11-16 17:17:13 -08:00
|
|
|
state = client.getMultirotorState()
|
|
|
|
|
if state.landed_state == airsim.LandedState.Landed:
|
2018-11-29 20:01:22 -08:00
|
|
|
print("taking off...")
|
|
|
|
|
client.takeoffAsync().join()
|
|
|
|
|
else:
|
|
|
|
|
client.hoverAsync().join()
|
2018-06-15 02:59:05 -07:00
|
|
|
|
2019-11-07 21:31:15 -08:00
|
|
|
time.sleep(1)
|
2019-11-16 17:17:13 -08:00
|
|
|
|
|
|
|
|
state = client.getMultirotorState()
|
|
|
|
|
if state.landed_state == airsim.LandedState.Landed:
|
2019-11-07 21:31:15 -08:00
|
|
|
print("take off failed...")
|
|
|
|
|
sys.exit(1)
|
|
|
|
|
|
2018-06-15 02:59:05 -07:00
|
|
|
# AirSim uses NED coordinates so negative axis is up.
|
2021-04-29 15:59:31 -07:00
|
|
|
# z of -5 is 5 meters above the original launch point.
|
|
|
|
|
z = -5
|
|
|
|
|
print("make sure we are hovering at {} meters...".format(-z))
|
2019-11-07 21:31:15 -08:00
|
|
|
client.moveToZAsync(z, 1).join()
|
2018-06-15 02:59:05 -07:00
|
|
|
|
|
|
|
|
# see https://github.com/Microsoft/AirSim/wiki/moveOnPath-demo
|
|
|
|
|
|
|
|
|
|
# this method is async and we are not waiting for the result since we are passing timeout_sec=0.
|
2019-11-07 21:31:15 -08:00
|
|
|
|
|
|
|
|
print("flying on path...")
|
2019-12-12 02:43:57 -08:00
|
|
|
result = client.moveOnPathAsync([airsim.Vector3r(125,0,z),
|
|
|
|
|
airsim.Vector3r(125,-130,z),
|
|
|
|
|
airsim.Vector3r(0,-130,z),
|
|
|
|
|
airsim.Vector3r(0,0,z)],
|
2019-11-07 21:31:15 -08:00
|
|
|
12, 120,
|
2018-06-17 04:19:13 -07:00
|
|
|
airsim.DrivetrainType.ForwardOnly, airsim.YawMode(False,0), 20, 1).join()
|
2019-11-09 15:27:48 -08:00
|
|
|
|
2019-11-11 14:48:32 -08:00
|
|
|
# drone will over-shoot so we bring it back to the start point before landing.
|
2018-06-15 21:27:58 -07:00
|
|
|
client.moveToPositionAsync(0,0,z,1).join()
|
2019-11-11 20:27:45 -08:00
|
|
|
print("landing...")
|
2018-11-30 21:26:46 -08:00
|
|
|
client.landAsync().join()
|
2019-11-11 20:27:45 -08:00
|
|
|
print("disarming...")
|
2018-06-15 02:59:05 -07:00
|
|
|
client.armDisarm(False)
|
|
|
|
|
client.enableApiControl(False)
|
2019-11-11 20:27:45 -08:00
|
|
|
print("done.")
|