def __init__(self, setpoint, minimax_z_thresh, max_xy_drift = (2,2)): # States will be pitch, roll, vx,vy,vz # Number of states = 5 s = np.zeros(8) self.current_state = np.array(s) # Initialize starting position initX = 0 # -.55265 initY = 0 # -31.9786 initZ = -1.5 # -19.0225 self.initial_position = (initX,initY,initZ) assert setpoint[2] <= 0 self.setpoint = setpoint assert minimax_z_thresh[0] >= 0 and minimax_z_thresh[1] >= 0 and minimax_z_thresh[0] < minimax_z_thresh[1] self.minimax_z_thresh = minimax_z_thresh assert max_xy_drift[0] > 0 and max_xy_drift[1] > 0 self.max_xy_drift = max_xy_drift # connect to the AirSim simulator print('Initializing Client') self.client = ASC.MultirotorClient() self.client.confirmConnection() self.client.enableApiControl(True) self.client.armDisarm(True) print('Initialization Complete!')
def getImg(self): responses = self.client.simGetImages([ AirSimClient.ImageRequest( 0, AirSimClient.AirSimImageType.DepthPerspective, True, False) ]) img1d = np.array(responses[0].image_data_float, dtype=np.float) img2d = np.reshape(img1d, (responses[0].height, responses[0].width)) image = Image.fromarray(img2d) im_final = np.array(image.resize((64, 64)).convert('L'), dtype=np.float) / 255 im_final.resize((64, 64)) #responses2 = self.client.simGetImages([AirSimClient.ImageRequest(0, AirSimClient.AirSimImageType.Segmentation, True, False)]) #img1d2 = np.array(responses2[0].image_data_float, dtype=np.float) #img2d2 = np.reshape(img1d2, (responses[0].height, responses[0].width)) #image2= Image.fromarray(img2d2) #im_final2 = np.array(image2.resize((64, 64)).convert('P'), dtype=np.float) / 255 if IMAGE_VIEW: cv2.imshow("view", im_final) key = cv2.waitKey(1) & 0xFF return im_final
def __init__(self, start=[0, 0, -5], aim=[32, 38, -4]): self.start = np.array(start) self.aim = np.array(aim) self.client = AirSimClient.MultirotorClient() self.client.confirmConnection() self.client.enableApiControl(True) self.client.armDisarm(True) self.threshold = goal_threshold
def moveByDist(self, diff, forward=False): temp = AirSimClient.YawMode() temp.is_rate = not forward self.client.moveByVelocity(diff[0], diff[1], diff[2], 1, drivetrain=AirSimClient.DrivetrainType.ForwardOnly, yaw_mode=temp) time.sleep(0.5) return 0
def moveByDist(self,diff, forward = False, duration = 1,yaw = None): if yaw is None: yaw = AirSimClient.YawMode() yaw.is_rate = not forward self.client.moveByVelocity(diff[0], diff[1], diff[2], duration ,drivetrain = AirSimClient.DrivetrainType.ForwardOnly, yaw_mode = yaw) time.sleep(1) return 0
def getImg(self): responses = self.client.simGetImages([ AirSimClient.ImageRequest( 0, AirSimClient.AirSimImageType.DepthPerspective, True, False) ]) img1d = np.array(responses[0].image_data_float, dtype=np.float) img1d = 255 * img1d img2d = np.reshape(img1d, (responses[0].height, responses[0].width)) image = Image.fromarray(img2d) im_final = np.array(image.resize((224, 224)).convert('L')) return im_final
def reset(self): cv2.destroyAllWindows() self.current_goal = -1 yaw = AirSimClient.YawMode() yaw.is_rate = False yaw.yaw_or_rate = drone_env.reset(self) time.sleep(2) self.change_goal() state = self.getState() self.state = state return state
def getImg(self): ''' responses = self.client.simGetImages([AirSimClient.ImageRequest(0, AirSimClient.AirSimImageType.DepthVis, True, False)]) img1 = np.array(responses[0].image_data_float, dtype=np.float) img2 = img1.reshape(responses[0].height, responses[0].width, 1)[:,:,0] image = Image.fromarray(img2) im_final = np.array([np.array(image.resize(IMG_SIZE))] ) return im_final ''' responses = self.client.simGetImages([AirSimClient.ImageRequest(0, AirSimClient.AirSimImageType.DepthPerspective, True, False)]) img1d = np.array(responses[0].image_data_float, dtype=np.float) img1d = 255/np.maximum(np.ones(img1d.size), img1d) img2d = np.reshape(img1d, (responses[0].height, responses[0].width)) image = Image.fromarray(img2d) im_final = np.array(image.resize(IMG_SIZE).convert('L')) return im_final
def __init__(self): # States will be pitch, roll, vx,vy,vz # Number of states = 5 s = np.zeros(8) self.current_state = np.array(s) # Initialize starting position initX = 0 # -.55265 initY = 0 # -31.9786 initZ = -1 # -19.0225 self.initial_position = (initX, initY, initZ) #self.initial_position = (0,0,0) # connect to the AirSim simulator print('Initializing Client') self.client = ASC.MultirotorClient() self.client.confirmConnection() self.client.enableApiControl(True) self.client.armDisarm(True) print('Initialization Complete!')
def __init__(self, minimax_z_thresh): # States will be pitch, roll, vx,vy,vz # Number of states = 4 states, + the 'RC' simulated action self.scaling_factor = .20 self.duration = .20 self.dt = 0 self.intervened = False # CHANGE THESE PER REQUIRED AGRRESIVITY # self.Lgain = .1 self.Ugain = .3 ######################################### self.drone_low_alt_count = 0 # keeps track of how many timesteps the drone has been under 1m self.num_user_RC_actions = 13 # 6 angular, 6 linear, one hover self.num_state_variables = 7 # posz, velz, roll, pitch self.total_state_variables = self.num_user_RC_actions + self.num_state_variables s = np.zeros(self.total_state_variables) self.current_state = np.array(s) self.current_state = np.array(s) #assert minimax_z_thresh[0] >= 0 and minimax_z_thresh[1] >= 0 and minimax_z_thresh[0] < minimax_z_thresh[1] self.minimax_z_thresh = minimax_z_thresh self.lb = pp.LabelBinarizer( ) # Binarizer for making categorical RC action input self.lb.fit(range(self.num_user_RC_actions)) # actions 0-12 # connect to the AirSim simulator print('Initializing Client') self.client = ASC.MultirotorClient() self.client.confirmConnection() self.client.enableApiControl(True) self.client.armDisarm(True) print('Initialization Complete!')
f = open(fileName, "w") for x in xrange(image.shape[0]): for y in xrange(image.shape[1]): pt = image[x, y] if (math.isinf(pt[0]) or math.isnan(pt[0])): # skip it None else: f.write("%f %f %f %s\n" % (pt[0], pt[1], pt[2] - 1, rgb)) f.close() for arg in sys.argv[1:]: cloud.txt = arg client = AirSimClient('127.0.0.1') while True: rawImage = client.getImageForCamera(0, AirSimImageType.Depth) if (rawImage is None): print( "Camera is not returning image, please check airsim for error messages" ) sys.exit(0) else: png = cv2.imdecode(rawImage, cv2.IMREAD_UNCHANGED) gray = cv2.cvtColor(png, cv2.COLOR_BGR2GRAY) Image3D = cv2.reprojectImageTo3D(gray, projectionMatrix) savePointCloud(Image3D, outputFile) print("saved " + outputFile) sys.exit(0)
#!/usr/bin/env python import rospy, time import AirSimClient as airsim from std_msgs.msg import String if __name__ == '__main__': rospy.init_node("image_publisher", anonymous=False) pub_img_depth = rospy.Publisher('camera/images/depth', String, queue_size=1) pub_img_segmentation = rospy.Publisher('camera/images/segmentation', String, queue_size=1) pub_img_scene = rospy.Publisher('camera/images/scene', String, queue_size=1) client = airsim.MultirotorClient("127.0.0.1") client.confirmConnection() time.sleep(1) while True: img_depth = client.simGetImage(0, airsim.AirSimImageType.DepthVis) img_segmentation = client.simGetImage(0, airsim.AirSimImageType.Segmentation) img_scene = client.simGetImage(0, airsim.AirSimImageType.Scene) if img_depth != None: pub_img_depth.publish(String(img_depth)) if img_segmentation != None: pub_img_segmentation.publish(String(img_segmentation)) if img_depth != None:
import setup_path #import airsim # new games build with airsim 1.3, both car and rotar port 41451 import AirSimClient as airsim # for games build with old version of airsim, car port 42451, rotar 41451 import cv2 import numpy as np import os import time import tempfile # connect to the AirSim simulator client = airsim.CarClient() client.confirmConnection() client.enableApiControl(True) print("API Control enabled: %s" % client.isApiControlEnabled()) car_controls = airsim.CarControls() #tmp_dir = os.path.join(tempfile.gettempdir(), "airsim_car") tmp_dir = os.path.join("./", "airsim_car") print ("Saving images to %s" % tmp_dir) try: os.makedirs(tmp_dir) except OSError: if not os.path.isdir(tmp_dir): raise for idx in range(3): # get state of the car