diff --git a/api/cpp/doctrees/environment.pickle b/api/cpp/doctrees/environment.pickle index 33b63a92..18af78dd 100644 Binary files a/api/cpp/doctrees/environment.pickle and b/api/cpp/doctrees/environment.pickle differ diff --git a/api/python/doctrees/api/autonomysim.ai.doctree b/api/python/doctrees/api/autonomysim.ai.doctree new file mode 100644 index 00000000..ab9b8d9a Binary files /dev/null and b/api/python/doctrees/api/autonomysim.ai.doctree differ diff --git a/api/python/doctrees/api/autonomysim.ai.imitation.doctree b/api/python/doctrees/api/autonomysim.ai.imitation.doctree new file mode 100644 index 00000000..2c8e66c8 Binary files /dev/null and b/api/python/doctrees/api/autonomysim.ai.imitation.doctree differ diff --git a/api/python/doctrees/api/autonomysim.ai.reinforcement.doctree b/api/python/doctrees/api/autonomysim.ai.reinforcement.doctree new file mode 100644 index 00000000..147774a7 Binary files /dev/null and b/api/python/doctrees/api/autonomysim.ai.reinforcement.doctree differ diff --git a/api/python/doctrees/api/autonomysim.ai.vision.doctree b/api/python/doctrees/api/autonomysim.ai.vision.doctree new file mode 100644 index 00000000..ca28e8da Binary files /dev/null and b/api/python/doctrees/api/autonomysim.ai.vision.doctree differ diff --git a/api/python/doctrees/api/autonomysim.doctree b/api/python/doctrees/api/autonomysim.doctree index c3e4228a..78adf149 100644 Binary files a/api/python/doctrees/api/autonomysim.doctree and b/api/python/doctrees/api/autonomysim.doctree differ diff --git a/api/python/doctrees/api/autonomysim.gym.doctree b/api/python/doctrees/api/autonomysim.gym.doctree new file mode 100644 index 00000000..5698283d Binary files /dev/null and b/api/python/doctrees/api/autonomysim.gym.doctree differ diff --git a/api/python/doctrees/api/autonomysim.gym.envs.doctree b/api/python/doctrees/api/autonomysim.gym.envs.doctree new file mode 100644 index 00000000..50f2df5a Binary files /dev/null and b/api/python/doctrees/api/autonomysim.gym.envs.doctree differ diff --git a/api/python/doctrees/api/autonomysim.sensors.doctree b/api/python/doctrees/api/autonomysim.sensors.doctree new file mode 100644 index 00000000..88c60bc6 Binary files /dev/null and b/api/python/doctrees/api/autonomysim.sensors.doctree differ diff --git a/api/python/doctrees/api/autonomysim.unreal.doctree b/api/python/doctrees/api/autonomysim.unreal.doctree new file mode 100644 index 00000000..34a0f6f1 Binary files /dev/null and b/api/python/doctrees/api/autonomysim.unreal.doctree differ diff --git a/api/python/doctrees/api/autonomysim.utils.doctree b/api/python/doctrees/api/autonomysim.utils.doctree new file mode 100644 index 00000000..9a8c638f Binary files /dev/null and b/api/python/doctrees/api/autonomysim.utils.doctree differ diff --git a/api/python/doctrees/api/autonomysim.utils.io.doctree b/api/python/doctrees/api/autonomysim.utils.io.doctree new file mode 100644 index 00000000..c57c8dc2 Binary files /dev/null and b/api/python/doctrees/api/autonomysim.utils.io.doctree differ diff --git a/api/python/doctrees/api/modules.doctree b/api/python/doctrees/api/modules.doctree new file mode 100644 index 00000000..858c3097 Binary files /dev/null and b/api/python/doctrees/api/modules.doctree differ diff --git a/api/python/doctrees/environment.pickle b/api/python/doctrees/environment.pickle index a4a2e6ee..2a75b7f1 100644 Binary files a/api/python/doctrees/environment.pickle and b/api/python/doctrees/environment.pickle differ diff --git a/api/python/doctrees/index.doctree b/api/python/doctrees/index.doctree index 70d2dc28..cbdb686a 100644 Binary files a/api/python/doctrees/index.doctree and b/api/python/doctrees/index.doctree differ diff --git a/api/python/html/_modules/autonomysim/client.html b/api/python/html/_modules/autonomysim/client.html index f2d525c9..daaba879 100644 --- a/api/python/html/_modules/autonomysim/client.html +++ b/api/python/html/_modules/autonomysim/client.html @@ -32,10 +32,9 @@ - + - - + @@ -196,94 +195,6 @@
- -
-
-
- - - - - - -
-
-
- @@ -310,7 +221,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] class VehicleClient: def __init__(self, ip="", port=41451, timeout_value=3600): if ip == "": @@ -324,7 +235,7 @@

Source code for autonomysim.client

 
     # ----------------------------------- Common vehicle APIs ---------------------------------------------
 
-[docs] +[docs] def reset(self): """ Reset the vehicle to its original starting state @@ -335,7 +246,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def ping(self): """ If connection is established then this call will return true otherwise it will be blocked until timeout @@ -347,32 +258,32 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getClientVersion(self): return 1 # sync with C++ client
-[docs] +[docs] def getServerVersion(self): return self.client.call("getServerVersion")
-[docs] +[docs] def getMinRequiredServerVersion(self): return 1 # sync with C++ client
-[docs] +[docs] def getMinRequiredClientVersion(self): return self.client.call("getMinRequiredClientVersion")
# basic flight control
-[docs] +[docs] def enableApiControl(self, is_enabled, vehicle_name=""): """ Enables or disables API control for vehicle corresponding to vehicle_name @@ -385,7 +296,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def isApiControlEnabled(self, vehicle_name=""): """ Returns true if API control is established. @@ -402,7 +313,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def armDisarm(self, arm, vehicle_name=""): """ Arms or disarms vehicle @@ -418,7 +329,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPause(self, is_paused): """ Pauses simulation @@ -430,7 +341,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simIsPause(self): """ Returns true if the simulation is paused @@ -442,7 +353,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simContinueForTime(self, seconds): """ Continue the simulation for the specified number of seconds @@ -454,7 +365,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simContinueForFrames(self, frames): """ Continue (or resume if paused) the simulation for the specified number of frames, after which the simulation will be paused. @@ -466,7 +377,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getHomeGeoPoint(self, vehicle_name=""): """ Get the Home location of the vehicle @@ -481,7 +392,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def confirmConnection(self): """ Checks state of connection every 1 sec and reports it in Console so user can see the progress for connection. @@ -523,7 +434,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetLightIntensity(self, light_name, intensity): """ Change intensity of named light @@ -539,7 +450,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSwapTextures(self, tags, tex_id=0, component_id=0, material_id=0): """ Runtime Swap Texture API @@ -563,7 +474,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetObjectMaterial(self, object_name, material_name, component_id=0): """ Runtime Swap Texture API @@ -582,7 +493,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetObjectMaterialFromTexture( self, object_name, texture_path, component_id=0 ): @@ -605,7 +516,7 @@

Source code for autonomysim.client

     # time-of-day control
     # time - of - day control
 
-[docs] +[docs] def simSetTimeOfDay( self, is_enabled, @@ -644,7 +555,7 @@

Source code for autonomysim.client

 
     # weather
 
-[docs] +[docs] def simEnableWeather(self, enable): """ Enable Weather effects. Needs to be called before using `simSetWeatherParameter` API @@ -656,7 +567,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetWeatherParameter(self, param, val): """ Enable various weather effects @@ -672,7 +583,7 @@

Source code for autonomysim.client

     # simGetImage returns compressed png in array of bytes
     # image_type uses one of the ImageType members
 
-[docs] +[docs] def simGetImage(self, camera_name, image_type, vehicle_name="", external=False): """ Get a single image @@ -706,7 +617,7 @@

Source code for autonomysim.client

     # simGetImage returns compressed png in array of bytes
     # image_type uses one of the ImageType members
 
-[docs] +[docs] def simGetImages(self, requests, vehicle_name="", external=False): """ Get multiple images @@ -731,7 +642,7 @@

Source code for autonomysim.client

 
     # CinemAutonomySim
 
-[docs] +[docs] def simGetPresetLensSettings(self, camera_name, vehicle_name="", external=False): result = self.client.call( "simGetPresetLensSettings", camera_name, vehicle_name, external @@ -742,7 +653,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetLensSettings(self, camera_name, vehicle_name="", external=False): result = self.client.call( "simGetLensSettings", camera_name, vehicle_name, external @@ -753,7 +664,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetPresetLensSettings( self, preset_lens_settings, camera_name, vehicle_name="", external=False ): @@ -767,7 +678,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetPresetFilmbackSettings( self, camera_name, vehicle_name="", external=False ): @@ -780,7 +691,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetPresetFilmbackSettings( self, preset_filmback_settings, camera_name, vehicle_name="", external=False ): @@ -794,7 +705,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetFilmbackSettings(self, camera_name, vehicle_name="", external=False): result = self.client.call( "simGetFilmbackSettings", camera_name, vehicle_name, external @@ -805,7 +716,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetFilmbackSettings( self, sensor_width, sensor_height, camera_name, vehicle_name="", external=False ): @@ -820,7 +731,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetFocalLength(self, camera_name, vehicle_name="", external=False): return self.client.call( "simGetFocalLength", camera_name, vehicle_name, external @@ -828,7 +739,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetFocalLength( self, focal_length, camera_name, vehicle_name="", external=False ): @@ -838,7 +749,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simEnableManualFocus( self, enable, camera_name, vehicle_name="", external=False ): @@ -848,7 +759,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetFocusDistance(self, camera_name, vehicle_name="", external=False): return self.client.call( "simGetFocusDistance", camera_name, vehicle_name, external @@ -856,7 +767,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetFocusDistance( self, focus_distance, camera_name, vehicle_name="", external=False ): @@ -866,7 +777,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetFocusAperture(self, camera_name, vehicle_name="", external=False): return self.client.call( "simGetFocusAperture", camera_name, vehicle_name, external @@ -874,7 +785,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetFocusAperture( self, focus_aperture, camera_name, vehicle_name="", external=False ): @@ -884,7 +795,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simEnableFocusPlane(self, enable, camera_name, vehicle_name="", external=False): self.client.call( "simEnableFocusPlane", enable, camera_name, vehicle_name, external @@ -892,7 +803,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetCurrentFieldOfView(self, camera_name, vehicle_name="", external=False): return self.client.call( "simGetCurrentFieldOfView", camera_name, vehicle_name, external @@ -901,7 +812,7 @@

Source code for autonomysim.client

 
     # End CinemAutonomySim
 
-[docs] +[docs] def simTestLineOfSightToPoint(self, point, vehicle_name=""): """ Returns whether the target point is visible from the perspective of the inputted vehicle @@ -917,7 +828,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simTestLineOfSightBetweenPoints(self, point1, point2): """ Returns whether the target point is visible from the perspective of the source point @@ -933,7 +844,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetWorldExtents(self): """ Returns a list of GeoPoints representing the minimum and maximum extents of the world @@ -946,7 +857,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simRunConsoleCommand(self, command): """ Allows the client to execute a command in Unreal's native console, via an API. @@ -964,7 +875,7 @@

Source code for autonomysim.client

 
     # gets the static meshes in the unreal scene
 
-[docs] +[docs] def simGetMeshPositionVertexBuffers(self): """ Returns the static meshes that make up the scene @@ -982,7 +893,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetCollisionInfo(self, vehicle_name=""): """ Args: @@ -997,7 +908,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetVehiclePose(self, pose, ignore_collision, vehicle_name=""): """ Set the pose of the vehicle @@ -1013,7 +924,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetVehiclePose(self, vehicle_name=""): """ The position inside the returned Pose is in the frame of the vehicle's starting point @@ -1029,7 +940,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetTraceLine(self, color_rgba, thickness=1.0, vehicle_name=""): """ Modify the color and thickness of the line when Tracing is enabled @@ -1045,7 +956,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetObjectPose(self, object_name): """ The position inside the returned Pose is in the world frame @@ -1061,7 +972,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetObjectPose(self, object_name, pose, teleport=True): """ Set the pose of the object(actor) in the environment @@ -1081,7 +992,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetObjectScale(self, object_name): """ Gets scale of an object in the world @@ -1097,7 +1008,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetObjectScale(self, object_name, scale_vector): """ Sets scale of an object in the world @@ -1113,7 +1024,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simListSceneObjects(self, name_regex=".*"): """ Lists the objects present in the environment @@ -1130,7 +1041,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simLoadLevel(self, level_name): """ Loads a level specified by its name @@ -1145,7 +1056,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simListAssets(self): """ Lists all the assets present in the Asset Registry @@ -1157,7 +1068,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSpawnObject( self, object_name, @@ -1192,7 +1103,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simDestroyObject(self, object_name): """Removes selected object from the world @@ -1206,7 +1117,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetSegmentationObjectID(self, mesh_name, object_id, is_name_regex=False): """ Set segmentation ID for specific objects @@ -1229,7 +1140,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetSegmentationObjectID(self, mesh_name): """ Returns Object ID for the given mesh name @@ -1243,7 +1154,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simAddDetectionFilterMeshName( self, camera_name, image_type, mesh_name, vehicle_name="", external=False ): @@ -1271,7 +1182,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetDetectionFilterRadius( self, camera_name, image_type, radius_cm, vehicle_name="", external=False ): @@ -1296,7 +1207,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simClearDetectionMeshNames( self, camera_name, image_type, vehicle_name="", external=False ): @@ -1320,7 +1231,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetDetections( self, camera_name, image_type, vehicle_name="", external=False ): @@ -1345,7 +1256,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPrintLogMessage(self, message, message_param="", severity=0): """ Prints the specified message in the simulator's window. @@ -1365,7 +1276,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetCameraInfo(self, camera_name, vehicle_name="", external=False): """ Get details about the camera @@ -1387,7 +1298,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetDistortionParams(self, camera_name, vehicle_name="", external=False): """ Get camera distortion parameters @@ -1407,7 +1318,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetDistortionParams( self, camera_name, distortion_params, vehicle_name="", external=False ): @@ -1429,7 +1340,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetDistortionParam( self, camera_name, param_name, value, vehicle_name="", external=False ): @@ -1454,7 +1365,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetCameraPose(self, camera_name, pose, vehicle_name="", external=False): """ - Control the pose of a selected camera @@ -1472,7 +1383,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetCameraFov( self, camera_name, fov_degrees, vehicle_name="", external=False ): @@ -1492,7 +1403,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetGroundTruthKinematics(self, vehicle_name=""): """ Get Ground truth kinematics of the vehicle @@ -1512,7 +1423,7 @@

Source code for autonomysim.client

     simGetGroundTruthKinematics.__annotations__ = {"return": KinematicsState}
 
 
-[docs] +[docs] def simSetKinematics(self, state, ignore_collision, vehicle_name=""): """ Set the kinematics state of the vehicle @@ -1528,7 +1439,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetGroundTruthEnvironment(self, vehicle_name=""): """ Get ground truth environment state @@ -1549,7 +1460,7 @@

Source code for autonomysim.client

 
     # sensor APIs
 
-[docs] +[docs] def getImuData(self, imu_name="", vehicle_name=""): """ Args: @@ -1565,7 +1476,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getBarometerData(self, barometer_name="", vehicle_name=""): """ Args: @@ -1581,7 +1492,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getMagnetometerData(self, magnetometer_name="", vehicle_name=""): """ Args: @@ -1597,7 +1508,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getGpsData(self, gps_name="", vehicle_name=""): """ Args: @@ -1613,7 +1524,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getDistanceSensorData(self, distance_sensor_name="", vehicle_name=""): """ Args: @@ -1631,7 +1542,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getLidarData(self, lidar_name="", vehicle_name=""): """ Args: @@ -1647,7 +1558,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simGetLidarSegmentation(self, lidar_name="", vehicle_name=""): """ NOTE: Deprecated API, use `getLidarData()` API instead @@ -1668,7 +1579,7 @@

Source code for autonomysim.client

 
     # Plotting APIs
 
-[docs] +[docs] def simFlushPersistentMarkers(self): """ Clear any persistent markers - those plotted with setting `is_persistent=True` in the APIs below @@ -1677,7 +1588,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotPoints( self, points, @@ -1702,7 +1613,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotLineStrip( self, points, @@ -1727,7 +1638,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotLineList( self, points, @@ -1752,7 +1663,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotArrows( self, points_start, @@ -1788,7 +1699,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotStrings( self, strings, @@ -1813,7 +1724,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotTransforms( self, poses, scale=5.0, thickness=5.0, duration=-1.0, is_persistent=False ): @@ -1833,7 +1744,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simPlotTransformsWithNames( self, poses, @@ -1869,7 +1780,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def cancelLastTask(self, vehicle_name=""): """ Cancel previous Async task @@ -1882,7 +1793,7 @@

Source code for autonomysim.client

 
     # Recording APIs
 
-[docs] +[docs] def startRecording(self): """ Start Recording @@ -1893,7 +1804,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def stopRecording(self): """ Stop Recording @@ -1902,7 +1813,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def isRecording(self): """ Whether Recording is running or not @@ -1914,7 +1825,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetWind(self, wind): """ Set simulated wind, in World frame, NED direction, m/s @@ -1926,7 +1837,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simCreateVoxelGrid(self, position, x, y, z, res, of): """ Construct and save a binvox-formatted voxel grid of environment @@ -1945,7 +1856,7 @@

Source code for autonomysim.client

 
     # Add new vehicle via RPC
 
-[docs] +[docs] def simAddVehicle(self, vehicle_name, vehicle_type, pose, pawn_path=""): """ Create vehicle at runtime @@ -1965,7 +1876,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def listVehicles(self): """ Lists the names of current vehicles @@ -1977,7 +1888,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getSettingsString(self): """ Fetch the settings text being used by AutonomySim @@ -1989,7 +1900,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def simSetExtForce(self, ext_force): """ Set arbitrary external forces, in World frame, NED direction. Can be used @@ -2005,13 +1916,13 @@

Source code for autonomysim.client

 
 # -----------------------------------  Multirotor APIs ---------------------------------------------
 
-[docs] +[docs] class MultirotorClient(VehicleClient, object): def __init__(self, ip="", port=41451, timeout_value=3600): super(MultirotorClient, self).__init__(ip, port, timeout_value)
-[docs] +[docs] def takeoffAsync(self, timeout_sec=20, vehicle_name=""): """ Takeoff vehicle to 3m above ground. Vehicle should not be moving when this API is used @@ -2027,7 +1938,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def landAsync(self, timeout_sec=60, vehicle_name=""): """ Land the vehicle @@ -2043,7 +1954,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def goHomeAsync(self, timeout_sec=3e38, vehicle_name=""): """ Return vehicle to Home i.e. Launch location @@ -2060,7 +1971,7 @@

Source code for autonomysim.client

 
     # APIs for control
 
-[docs] +[docs] def moveByVelocityBodyFrameAsync( self, vx, @@ -2077,9 +1988,9 @@

Source code for autonomysim.client

             vy (float): desired velocity in the Y axis of the vehicle's local NED frame.
             vz (float): desired velocity in the Z axis of the vehicle's local NED frame.
             duration (float): Desired amount of time (seconds), to send this command for
-            drivetrain=0 (DrivetrainType, optional):
-            yaw_mode=<YawMode> (YawMode, optional):
-            vehicle_name='' (str, optional): Name of the multirotor to send this command to
+            drivetrain (DrivetrainType, optional):
+            yaw_mode (YawMode, optional):
+            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()
@@ -2097,7 +2008,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByVelocityZBodyFrameAsync( self, vx, @@ -2114,9 +2025,9 @@

Source code for autonomysim.client

             vy (float): desired velocity in the Y axis of the vehicle's local NED frame
             z (float): desired Z value (in local NED frame of the vehicle)
             duration (float): Desired amount of time (seconds), to send this command for
-            drivetrain=0 (DrivetrainType, optional):
-            yaw_mode=<YawMode> (YawMode, optional):
-            vehicle_name='' (str, optional): Name of the multirotor to send this command to
+            drivetrain (DrivetrainType, optional):
+            yaw_mode (YawMode, optional):
+            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()
@@ -2135,7 +2046,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByAngleZAsync(self, pitch, roll, z, yaw, duration, vehicle_name=""): logging.warning( "moveByAngleZAsync API is deprecated, use moveByRollPitchYawZAsync() API instead" @@ -2146,7 +2057,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByAngleThrottleAsync( self, pitch, roll, throttle, yaw_rate, duration, vehicle_name="" ): @@ -2165,7 +2076,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByVelocityAsync( self, vx, @@ -2182,9 +2093,9 @@

Source code for autonomysim.client

             vy (float): desired velocity in world (NED) Y axis
             vz (float): desired velocity in world (NED) Z axis
             duration (float): Desired amount of time (seconds), to send this command for
-            drivetrain=0 (DrivetrainType, optional):
-            yaw_mode=<YawMode> (YawMode, optional):
-            vehicle_name='' (str, optional): Name of the multirotor to send this command to
+            drivetrain (DrivetrainType, optional):
+            yaw_mode (YawMode, optional):
+            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()
@@ -2195,7 +2106,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByVelocityZAsync( self, vx, @@ -2212,7 +2123,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveOnPathAsync( self, path, @@ -2238,7 +2149,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveToPositionAsync( self, x, @@ -2268,7 +2179,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveToGPSAsync( self, latitude, @@ -2298,7 +2209,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveToZAsync( self, z, @@ -2322,7 +2233,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByManualAsync( self, vx_max, @@ -2334,20 +2245,20 @@

Source code for autonomysim.client

         vehicle_name="",
     ):
         """
-        Read current RC state and use it to control the vehicles.
+        - Read current RC state and use it to control the vehicles.
 
-        Parameters setup the constraints on velocity and minimum altitude while flying. If RC state is detected to violate these constraints,
+        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.
 
         Args:
             vx_max (float): max velocity allowed in x direction
             vy_max (float): max velocity allowed in y direction
+            vz_max (float): max velocity allowed in z direction
             z_min (float): min z allowed for vehicle position
             duration (float): after this duration vehicle would switch back to non-manual mode
-            drivetrain=0 (DrivetrainType): when ForwardOnly, vehicle rotates itself so that its front is always facing the direction of travel. If MaxDegreeOfFreedom then it doesn't do that and instead does crab-like movement
-            yaw_mode=<YawMode> (YawMode): Specifies if vehicle should face at given angle (is_rate=False) or should be rotating around its axis at given rate (is_rate=True)
-            vehicle_name='' (str, optional): Name of the multirotor to send this command to
-
+            drivetrain (DrivetrainType): 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)
+            yaw_mode (YawMode): Specifies if vehicle should face at given angle (is_rate=False) or should be rotating around its axis at given rate (is_rate=True)
+            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()
         """
@@ -2364,7 +2275,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def rotateToYawAsync(self, yaw, timeout_sec=3e38, margin=5, vehicle_name=""): return self.client.call_async( "rotateToYaw", yaw, timeout_sec, margin, vehicle_name @@ -2372,7 +2283,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def rotateByYawRateAsync(self, yaw_rate, duration, vehicle_name=""): return self.client.call_async( "rotateByYawRate", yaw_rate, duration, vehicle_name @@ -2380,20 +2291,20 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def hoverAsync(self, vehicle_name=""): return self.client.call_async("hover", vehicle_name)
-[docs] +[docs] def moveByRC(self, rcdata=RCData(), vehicle_name=""): return self.client.call("moveByRC", rcdata, vehicle_name)
# low - level control API
-[docs] +[docs] def moveByMotorPWMsAsync( self, front_right_pwm, @@ -2428,7 +2339,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByRollPitchYawZAsync(self, roll, pitch, yaw, z, duration, vehicle_name=""): """ - z is given in local NED frame of the vehicle. @@ -2468,7 +2379,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByRollPitchYawThrottleAsync( self, roll, pitch, yaw, throttle, duration, vehicle_name="" ): @@ -2516,7 +2427,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByRollPitchYawrateThrottleAsync( self, roll, pitch, yaw_rate, throttle, duration, vehicle_name="" ): @@ -2564,7 +2475,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByRollPitchYawrateZAsync( self, roll, pitch, yaw_rate, z, duration, vehicle_name="" ): @@ -2612,7 +2523,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByAngleRatesZAsync( self, roll_rate, pitch_rate, yaw_rate, z, duration, vehicle_name="" ): @@ -2660,7 +2571,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def moveByAngleRatesThrottleAsync( self, roll_rate, pitch_rate, yaw_rate, throttle, duration, vehicle_name="" ): @@ -2708,7 +2619,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def setAngleRateControllerGains( self, angle_rate_gains=AngleRateControllerGains(), vehicle_name="" ): @@ -2719,10 +2630,10 @@

Source code for autonomysim.client

         - This function should only be called if the default angle rate control PID gains need to be modified.
 
         Args:
-            angle_rate_gains=<AngleRateControllerGains> (AngleRateControllerGains):
+            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
+            vehicle_name (str, optional): Name of the multirotor to send this command to
         """
         self.client.call(
             "setAngleRateControllerGains",
@@ -2731,7 +2642,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def setAngleLevelControllerGains( self, angle_level_gains=AngleLevelControllerGains(), vehicle_name="" ): @@ -2743,10 +2654,10 @@

Source code for autonomysim.client

         - Passing AngleLevelControllerGains() sets gains to default AutonomySim values.
 
         Args:
-            angle_level_gains=<AngleLevelControllerGains> (AngleLevelControllerGains):
+            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
+            vehicle_name (str, optional): Name of the multirotor to send this command to
         """
         self.client.call(
             "setAngleLevelControllerGains",
@@ -2755,7 +2666,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def setVelocityControllerGains( self, velocity_gains=VelocityControllerGains(), vehicle_name="" ): @@ -2765,11 +2676,11 @@

Source code for autonomysim.client

         - Passing VelocityControllerGains() sets gains to default AutonomySim values.
 
         Args:
-            velocity_gains=<VelocityControllerGains> (VelocityControllerGains):
+            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
+            vehicle_name (str, optional): Name of the multirotor to send this command to
         """
         self.client.call(
             "setVelocityControllerGains", *(velocity_gains.to_lists() + (vehicle_name,))
@@ -2777,7 +2688,7 @@ 

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def setPositionControllerGains( self, position_gains=PositionControllerGains(), vehicle_name="" ): @@ -2786,10 +2697,10 @@

Source code for autonomysim.client

         This function should only be called if the default position control PID gains need to be modified.
 
         Args:
-            position_gains=<PositionControllerGains> (PositionControllerGains):
+            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
+            vehicle_name (str, optional): Name of the multirotor to send this command to
         """
         self.client.call(
             "setPositionControllerGains", *(position_gains.to_lists() + (vehicle_name,))
@@ -2798,7 +2709,7 @@ 

Source code for autonomysim.client

 
     # query vehicle state
 
-[docs] +[docs] def getMultirotorState(self, vehicle_name=""): """ The position inside the returned MultirotorState is in the frame of the vehicle's starting point @@ -2818,7 +2729,7 @@

Source code for autonomysim.client

 
     # query rotor states
 
-[docs] +[docs] def getRotorStates(self, vehicle_name=""): """ Used to obtain the current state of all a multirotor's rotors. The state includes the speeds, @@ -2841,13 +2752,13 @@

Source code for autonomysim.client

 
 # ----------------------------------- Car APIs ---------------------------------------------
 
-[docs] +[docs] class CarClient(VehicleClient, object): def __init__(self, ip="", port=41451, timeout_value=3600): super(CarClient, self).__init__(ip, port, timeout_value)
-[docs] +[docs] def setCarControls(self, controls, vehicle_name=""): """ Control the car using throttle, steering, brake, etc. @@ -2860,7 +2771,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getCarState(self, vehicle_name=""): """ The position inside the returned CarState is in the frame of the vehicle's starting point @@ -2876,7 +2787,7 @@

Source code for autonomysim.client

 
 
 
-[docs] +[docs] def getCarControls(self, vehicle_name=""): """ Args: diff --git a/api/python/html/_modules/autonomysim/clients.html b/api/python/html/_modules/autonomysim/clients.html new file mode 100644 index 00000000..c3dd12d5 --- /dev/null +++ b/api/python/html/_modules/autonomysim/clients.html @@ -0,0 +1,2984 @@ + + + + + + + + + + + + + + + + autonomysim.clients - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+
+ +
+ + + + + + +
+ + +
+ +
+ + + + + + + + +
+
+ + + +
+
+
+ + + + + + +
+
+
+ + + + +
+
+ + + + + + + + +

Source code for autonomysim.clients

+import msgpackrpc
+import logging
+# import numpy as np
+# import msgpack
+# import time
+# import math
+
+from autonomysim.types import *
+from autonomysim.utils import *
+
+
+
+[docs] +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 --------------------------------------------- +
+[docs] + def reset(self): + """ + Reset the vehicle to its original starting state + + Note that you must call `enableApiControl` and `armDisarm` again after the call to reset + """ + self.client.call("reset")
+ + +
+[docs] + def ping(self): + """ + If connection is established then this call will return true otherwise it will be blocked until timeout + + Returns: + bool: + """ + return self.client.call("ping")
+ + +
+[docs] + def getClientVersion(self): + return 1 # sync with C++ client
+ + +
+[docs] + def getServerVersion(self): + return self.client.call("getServerVersion")
+ + +
+[docs] + def getMinRequiredServerVersion(self): + return 1 # sync with C++ client
+ + +
+[docs] + def getMinRequiredClientVersion(self): + return self.client.call("getMinRequiredClientVersion")
+ + + # basic flight control +
+[docs] + 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)
+ + +
+[docs] + 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)
+ + +
+[docs] + def armDisarm(self, arm, vehicle_name=""): + """ + Arms or disarms vehicle + + Args: + arm (bool): True to arm, False to disarm the vehicle + vehicle_name (str, optional): Name of the vehicle to send this command to + + Returns: + bool: Success + """ + return self.client.call("armDisarm", arm, vehicle_name)
+ + +
+[docs] + def simPause(self, is_paused): + """ + Pauses simulation + + Args: + is_paused (bool): True to pause the simulation, False to release + """ + self.client.call("simPause", is_paused)
+ + +
+[docs] + def simIsPause(self): + """ + Returns true if the simulation is paused + + Returns: + bool: If the simulation is paused + """ + return self.client.call("simIsPaused")
+ + +
+[docs] + def simContinueForTime(self, seconds): + """ + Continue the simulation for the specified number of seconds + + Args: + seconds (float): Time to run the simulation for + """ + self.client.call("simContinueForTime", seconds)
+ + +
+[docs] + def simContinueForFrames(self, frames): + """ + Continue (or resume if paused) the simulation for the specified number of frames, after which the simulation will be paused. + + Args: + frames (int): Frames to run the simulation for + """ + self.client.call("simContinueForFrames", frames)
+ + +
+[docs] + def getHomeGeoPoint(self, vehicle_name=""): + """ + Get the Home location of the vehicle + + Args: + vehicle_name (str, optional): Name of vehicle to get home location of + + Returns: + GeoPoint: Home location of the vehicle + """ + return GeoPoint.from_msgpack(self.client.call("getHomeGeoPoint", vehicle_name))
+ + +
+[docs] + 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( + "AutonomySim 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( + "AutonomySim client is of older version and not supported by this server. Please upgrade!" + ) + else: + print(ver_info) + print("")
+ + +
+[docs] + def simSetLightIntensity(self, light_name, intensity): + """ + Change intensity of named light + + Args: + light_name (str): Name of light to change + intensity (float): New intensity value + + Returns: + bool: True if successful, otherwise False + """ + return self.client.call("simSetLightIntensity", light_name, intensity)
+ + +
+[docs] + def simSwapTextures(self, tags, tex_id=0, component_id=0, material_id=0): + """ + Runtime Swap Texture API + + See https://nervosys.github.io/AutonomySim/texture_swapping/ for details + + Args: + tags (str): string of "," or ", " delimited tags to identify on which actors to perform the swap + tex_id (int, optional): indexes the array of textures assigned to each actor undergoing a swap + + If out-of-bounds for some object's texture set, it will be taken modulo the number of textures that were available + component_id (int, optional): + material_id (int, optional): + + Returns: + list[str]: List of objects which matched the provided tags and had the texture swap perfomed + """ + return self.client.call( + "simSwapTextures", tags, tex_id, component_id, material_id + )
+ + +
+[docs] + def simSetObjectMaterial(self, object_name, material_name, component_id=0): + """ + Runtime Swap Texture API + See https://nervosys.github.io/AutonomySim/texture_swapping/ for details + Args: + object_name (str): name of object to set material for + material_name (str): name of material to set for object + component_id (int, optional) : index of material elements + + Returns: + bool: True if material was set + """ + return self.client.call( + "simSetObjectMaterial", object_name, material_name, component_id + )
+ + +
+[docs] + def simSetObjectMaterialFromTexture( + self, object_name, texture_path, component_id=0 + ): + """ + Runtime Swap Texture API + See https://nervosys.github.io/AutonomySim/texture_swapping/ for details + Args: + object_name (str): name of object to set material for + texture_path (str): path to texture to set for object + component_id (int, optional) : index of material elements + + Returns: + bool: True if material was set + """ + return self.client.call( + "simSetObjectMaterialFromTexture", object_name, texture_path, component_id + )
+ + + # time-of-day control + # time - of - day control +
+[docs] + def simSetTimeOfDay( + self, + is_enabled, + start_datetime="", + is_start_datetime_dst=False, + celestial_clock_speed=1, + update_interval_secs=60, + move_sun=True, + ): + """ + Control the position of Sun in the environment + + Sun's position is computed using the coordinates specified in `OriginGeopoint` in settings for the date-time specified in the argument, + else if the string is empty, current date & time is used + + Args: + is_enabled (bool): True to enable time-of-day effect, False to reset the position to original + start_datetime (str, optional): Date & Time in %Y-%m-%d %H:%M:%S format, e.g. `2018-02-12 15:20:00` + is_start_datetime_dst (bool, optional): True to adjust for Daylight Savings Time + celestial_clock_speed (float, optional): Run celestial clock faster or slower than simulation clock + E.g. Value 100 means for every 1 second of simulation clock, Sun's position is advanced by 100 seconds + so Sun will move in sky much faster + update_interval_secs (float, optional): Interval to update the Sun's position + move_sun (bool, optional): Whether or not to move the Sun + """ + self.client.call( + "simSetTimeOfDay", + is_enabled, + start_datetime, + is_start_datetime_dst, + celestial_clock_speed, + update_interval_secs, + move_sun, + )
+ + + # weather +
+[docs] + def simEnableWeather(self, enable): + """ + Enable Weather effects. Needs to be called before using `simSetWeatherParameter` API + + Args: + enable (bool): True to enable, False to disable + """ + self.client.call("simEnableWeather", enable)
+ + +
+[docs] + def simSetWeatherParameter(self, param, val): + """ + Enable various weather effects + + Args: + param (WeatherParameter): Weather effect to be enabled + val (float): Intensity of the effect, Range 0-1 + """ + self.client.call("simSetWeatherParameter", param, val)
+ + + # camera control + # simGetImage returns compressed png in array of bytes + # image_type uses one of the ImageType members +
+[docs] + def simGetImage(self, camera_name, image_type, vehicle_name="", external=False): + """ + Get a single image + + Returns bytes of png format image which can be dumped into abinary file to create .png image + `string_to_uint8_array()` can be used to convert into Numpy unit8 array + See https://nervosys.github.io/AutonomySim/apis_image/ for details + + 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): Name of the vehicle with the camera + external (bool, optional): Whether the camera is an External Camera + + Returns: + Binary string literal of compressed png image + """ + # 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, external + ) + 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 +
+[docs] + def simGetImages(self, requests, vehicle_name="", external=False): + """ + Get multiple images + + See https://nervosys.github.io/AutonomySim/apis_image/ 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 + ]
+ + + # CinemAutonomySim +
+[docs] + def simGetPresetLensSettings(self, camera_name, vehicle_name="", external=False): + result = self.client.call( + "simGetPresetLensSettings", camera_name, vehicle_name, external + ) + if result == "" or result == "\0": + return None + return result
+ + +
+[docs] + def simGetLensSettings(self, camera_name, vehicle_name="", external=False): + result = self.client.call( + "simGetLensSettings", camera_name, vehicle_name, external + ) + if result == "" or result == "\0": + return None + return result
+ + +
+[docs] + def simSetPresetLensSettings( + self, preset_lens_settings, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simSetPresetLensSettings", + preset_lens_settings, + camera_name, + vehicle_name, + external, + )
+ + +
+[docs] + def simGetPresetFilmbackSettings( + self, camera_name, vehicle_name="", external=False + ): + result = self.client.call( + "simGetPresetFilmbackSettings", camera_name, vehicle_name, external + ) + if result == "" or result == "\0": + return None + return result
+ + +
+[docs] + def simSetPresetFilmbackSettings( + self, preset_filmback_settings, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simSetPresetFilmbackSettings", + preset_filmback_settings, + camera_name, + vehicle_name, + external, + )
+ + +
+[docs] + def simGetFilmbackSettings(self, camera_name, vehicle_name="", external=False): + result = self.client.call( + "simGetFilmbackSettings", camera_name, vehicle_name, external + ) + if result == "" or result == "\0": + return None + return result
+ + +
+[docs] + def simSetFilmbackSettings( + self, sensor_width, sensor_height, camera_name, vehicle_name="", external=False + ): + return self.client.call( + "simSetFilmbackSettings", + sensor_width, + sensor_height, + camera_name, + vehicle_name, + external, + )
+ + +
+[docs] + def simGetFocalLength(self, camera_name, vehicle_name="", external=False): + return self.client.call( + "simGetFocalLength", camera_name, vehicle_name, external + )
+ + +
+[docs] + def simSetFocalLength( + self, focal_length, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simSetFocalLength", focal_length, camera_name, vehicle_name, external + )
+ + +
+[docs] + def simEnableManualFocus( + self, enable, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simEnableManualFocus", enable, camera_name, vehicle_name, external + )
+ + +
+[docs] + def simGetFocusDistance(self, camera_name, vehicle_name="", external=False): + return self.client.call( + "simGetFocusDistance", camera_name, vehicle_name, external + )
+ + +
+[docs] + def simSetFocusDistance( + self, focus_distance, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simSetFocusDistance", focus_distance, camera_name, vehicle_name, external + )
+ + +
+[docs] + def simGetFocusAperture(self, camera_name, vehicle_name="", external=False): + return self.client.call( + "simGetFocusAperture", camera_name, vehicle_name, external + )
+ + +
+[docs] + def simSetFocusAperture( + self, focus_aperture, camera_name, vehicle_name="", external=False + ): + self.client.call( + "simSetFocusAperture", focus_aperture, camera_name, vehicle_name, external + )
+ + +
+[docs] + def simEnableFocusPlane(self, enable, camera_name, vehicle_name="", external=False): + self.client.call( + "simEnableFocusPlane", enable, camera_name, vehicle_name, external + )
+ + +
+[docs] + def simGetCurrentFieldOfView(self, camera_name, vehicle_name="", external=False): + return self.client.call( + "simGetCurrentFieldOfView", camera_name, vehicle_name, external + )
+ + + # End CinemAutonomySim +
+[docs] + def simTestLineOfSightToPoint(self, point, vehicle_name=""): + """ + Returns whether the target point is visible from the perspective of the inputted vehicle + + Args: + point (GeoPoint): target point + vehicle_name (str, optional): Name of vehicle + + Returns: + [bool]: Success + """ + return self.client.call("simTestLineOfSightToPoint", point, vehicle_name)
+ + +
+[docs] + def simTestLineOfSightBetweenPoints(self, point1, point2): + """ + Returns whether the target point is visible from the perspective of the source point + + Args: + point1 (GeoPoint): source point + point2 (GeoPoint): target point + + Returns: + [bool]: Success + """ + return self.client.call("simTestLineOfSightBetweenPoints", point1, point2)
+ + +
+[docs] + def simGetWorldExtents(self): + """ + Returns a list of GeoPoints representing the minimum and maximum extents of the world + + Returns: + list[GeoPoint] + """ + responses_raw = self.client.call("simGetWorldExtents") + return [GeoPoint.from_msgpack(response_raw) for response_raw in responses_raw]
+ + +
+[docs] + def simRunConsoleCommand(self, command): + """ + Allows the client to execute a command in Unreal's native console, via an API. + Affords access to the countless built-in commands such as "stat unit", "stat fps", "open [map]", adjust any config settings, etc. etc. + Allows the user to create bespoke APIs very easily, by adding a custom event to the level blueprint, and then calling the console command "ce MyEventName [args]". No recompilation of AutonomySim needed! + + Args: + command ([string]): Desired Unreal Engine Console command to run + + Returns: + [bool]: Success + """ + return self.client.call("simRunConsoleCommand", command)
+ + + # gets the static meshes in the unreal scene +
+[docs] + def simGetMeshPositionVertexBuffers(self): + """ + Returns the static meshes that make up the scene + + See https://nervosys.github.io/AutonomySim/meshes/ for details and how to use this + + Returns: + list[MeshPositionVertexBuffersResponse]: + """ + responses_raw = self.client.call("simGetMeshPositionVertexBuffers") + return [ + MeshPositionVertexBuffersResponse.from_msgpack(response_raw) + for response_raw in responses_raw + ]
+ + +
+[docs] + def simGetCollisionInfo(self, vehicle_name=""): + """ + Args: + vehicle_name (str, optional): Name of the Vehicle to get the info of + + Returns: + CollisionInfo: + """ + return CollisionInfo.from_msgpack( + self.client.call("simGetCollisionInfo", vehicle_name) + )
+ + +
+[docs] + def simSetVehiclePose(self, pose, ignore_collision, vehicle_name=""): + """ + Set the pose of the vehicle + + If you don't want to change position (or orientation) then just set components of position (or orientation) to floating point nan values + + Args: + pose (Pose): Desired Pose pf the vehicle + ignore_collision (bool): Whether to ignore any collision or not + vehicle_name (str, optional): Name of the vehicle to move + """ + self.client.call("simSetVehiclePose", pose, ignore_collision, vehicle_name)
+ + +
+[docs] + def simGetVehiclePose(self, vehicle_name=""): + """ + The position inside the returned Pose is in the frame of the vehicle's starting point + + Args: + vehicle_name (str, optional): Name of the vehicle to get the Pose of + + Returns: + Pose: + """ + pose = self.client.call("simGetVehiclePose", vehicle_name) + return Pose.from_msgpack(pose)
+ + +
+[docs] + def simSetTraceLine(self, color_rgba, thickness=1.0, vehicle_name=""): + """ + Modify the color and thickness of the line when Tracing is enabled + + Tracing can be enabled by pressing T in the Editor or setting `EnableTrace` to `True` in the Vehicle Settings + + Args: + color_rgba (list): desired RGBA values from 0.0 to 1.0 + thickness (float, optional): Thickness of the line + vehicle_name (string, optional): Name of the vehicle to set Trace line values for + """ + self.client.call("simSetTraceLine", color_rgba, thickness, vehicle_name)
+ + +
+[docs] + def simGetObjectPose(self, object_name): + """ + The position inside the returned Pose is in the world frame + + Args: + object_name (str): Object to get the Pose of + + Returns: + Pose: + """ + pose = self.client.call("simGetObjectPose", object_name) + return Pose.from_msgpack(pose)
+ + +
+[docs] + def simSetObjectPose(self, object_name, pose, teleport=True): + """ + Set the pose of the object(actor) in the environment + + The specified actor must have Mobility set to movable, otherwise there will be undefined behaviour. + See https://www.unrealengine.com/en-US/blog/moving-physical-objects for details on how to set Mobility and the effect of Teleport parameter + + Args: + object_name (str): Name of the object(actor) to move + pose (Pose): Desired Pose of the object + teleport (bool, optional): Whether to move the object immediately without affecting their velocity + + Returns: + bool: If the move was successful + """ + return self.client.call("simSetObjectPose", object_name, pose, teleport)
+ + +
+[docs] + def simGetObjectScale(self, object_name): + """ + Gets scale of an object in the world + + Args: + object_name (str): Object to get the scale of + + Returns: + autonomysim.Vector3r: Scale + """ + scale = self.client.call("simGetObjectScale", object_name) + return Vector3r.from_msgpack(scale)
+ + +
+[docs] + def simSetObjectScale(self, object_name, scale_vector): + """ + Sets scale of an object in the world + + Args: + object_name (str): Object to set the scale of + scale_vector (autonomysim.Vector3r): Desired scale of object + + Returns: + bool: True if scale change was successful + """ + return self.client.call("simSetObjectScale", object_name, scale_vector)
+ + +
+[docs] + def simListSceneObjects(self, name_regex=".*"): + """ + Lists the objects present in the environment + + Default behaviour is to list all objects, regex can be used to return smaller list of matching objects or actors + + Args: + name_regex (str, optional): String to match actor names against, e.g. "Cylinder.*" + + Returns: + list[str]: List containing all the names + """ + return self.client.call("simListSceneObjects", name_regex)
+ + +
+[docs] + def simLoadLevel(self, level_name): + """ + Loads a level specified by its name + + Args: + level_name (str): Name of the level to load + + Returns: + bool: True if the level was successfully loaded + """ + return self.client.call("simLoadLevel", level_name)
+ + +
+[docs] + def simListAssets(self): + """ + Lists all the assets present in the Asset Registry + + Returns: + list[str]: Names of all the assets + """ + return self.client.call("simListAssets")
+ + +
+[docs] + def simSpawnObject( + self, + object_name, + asset_name, + pose, + scale, + physics_enabled=False, + is_blueprint=False, + ): + """Spawned selected object in the world + + Args: + object_name (str): Desired name of new object + asset_name (str): Name of asset(mesh) in the project database + pose (autonomysim.Pose): Desired pose of object + scale (autonomysim.Vector3r): Desired scale of object + physics_enabled (bool, optional): Whether to enable physics for the object + is_blueprint (bool, optional): Whether to spawn a blueprint or an actor + + Returns: + str: Name of spawned object, in case it had to be modified + """ + return self.client.call( + "simSpawnObject", + object_name, + asset_name, + pose, + scale, + physics_enabled, + is_blueprint, + )
+ + +
+[docs] + def simDestroyObject(self, object_name): + """Removes selected object from the world + + Args: + object_name (str): Name of object to be removed + + Returns: + bool: True if object is queued up for removal + """ + return self.client.call("simDestroyObject", object_name)
+ + +
+[docs] + def simSetSegmentationObjectID(self, mesh_name, object_id, is_name_regex=False): + """ + Set segmentation ID for specific objects + + See https://nervosys.github.io/AutonomySim/apis_image/#segmentation for details + + Args: + mesh_name (str): Name of the mesh to set the ID of (supports regex) + object_id (int): Object ID to be set, range 0-255 + + RBG values for IDs can be seen at https://nervosys.github.io/AutonomySim/files/configurations/seg_rgbs.txt + is_name_regex (bool, optional): Whether the mesh name is a regex + + Returns: + bool: If the mesh was found + """ + return self.client.call( + "simSetSegmentationObjectID", mesh_name, object_id, is_name_regex + )
+ + +
+[docs] + def simGetSegmentationObjectID(self, mesh_name): + """ + Returns Object ID for the given mesh name + + Mapping of Object IDs to RGB values can be seen at https://nervosys.github.io/AutonomySim/seg_rgbs.txt + + Args: + mesh_name (str): Name of the mesh to get the ID of + """ + return self.client.call("simGetSegmentationObjectID", mesh_name)
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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 + ]
+ + +
+[docs] + def simPrintLogMessage(self, message, message_param="", severity=0): + """ + Prints the specified message in the simulator's window. + + If message_param is supplied, then it's printed next to the message and in that case if this API is called with same message value + but different message_param again then previous line is overwritten with new line (instead of API creating new line on display). + + For example, `simPrintLogMessage("Iteration: ", to_string(i))` keeps updating same line on display when API is called with different values of i. + The valid values of severity parameter is 0 to 3 inclusive that corresponds to different colors. + + Args: + message (str): Message to be printed + message_param (str, optional): Parameter to be printed next to the message + severity (int, optional): Range 0-3, inclusive, corresponding to the severity of the message + """ + self.client.call("simPrintLogMessage", message, message_param, severity)
+ + +
+[docs] + def simGetCameraInfo(self, camera_name, vehicle_name="", external=False): + """ + Get details about the camera + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera + + Returns: + CameraInfo: + """ + # 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, external + ) + )
+ + +
+[docs] + def simGetDistortionParams(self, camera_name, vehicle_name="", external=False): + """ + Get camera distortion parameters + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera + + Returns: + List (float): List of distortion parameter values corresponding to K1, K2, K3, P1, P2 respectively. + """ + + return self.client.call( + "simGetDistortionParams", str(camera_name), vehicle_name, external + )
+ + +
+[docs] + def simSetDistortionParams( + self, camera_name, distortion_params, vehicle_name="", external=False + ): + """ + Set camera distortion parameters + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + distortion_params (dict): Dictionary of distortion param names and corresponding values + {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0} + vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera + """ + + for param_name, value in distortion_params.items(): + self.simSetDistortionParam( + camera_name, param_name, value, vehicle_name, external + )
+ + +
+[docs] + def simSetDistortionParam( + self, camera_name, param_name, value, vehicle_name="", external=False + ): + """ + Set single camera distortion parameter + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + param_name (str): Name of distortion parameter + value (float): Value of distortion parameter + vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera + """ + self.client.call( + "simSetDistortionParam", + str(camera_name), + param_name, + value, + vehicle_name, + external, + )
+ + +
+[docs] + def simSetCameraPose(self, camera_name, pose, vehicle_name="", external=False): + """ + - Control the pose of a selected camera + + Args: + camera_name (str): Name of the camera to be controlled + pose (Pose): Pose representing the desired position and orientation of the camera + vehicle_name (str, optional): Name of vehicle which the camera corresponds to + external (bool, optional): Whether the camera is an External Camera + """ + # TODO : below str() conversion is only needed for legacy reason and should be removed in future + self.client.call( + "simSetCameraPose", str(camera_name), pose, vehicle_name, external + )
+ + +
+[docs] + def simSetCameraFov( + self, camera_name, fov_degrees, vehicle_name="", external=False + ): + """ + - 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 + external (bool, optional): Whether the camera is an External Camera + """ + # TODO : below str() conversion is only needed for legacy reason and should be removed in future + self.client.call( + "simSetCameraFov", str(camera_name), fov_degrees, vehicle_name, external + )
+ + +
+[docs] + def simGetGroundTruthKinematics(self, vehicle_name=""): + """ + Get Ground truth kinematics of the vehicle + + The position inside the returned KinematicsState is in the frame of the vehicle's starting point + + Args: + vehicle_name (str, optional): Name of the vehicle + + Returns: + KinematicsState: Ground truth of the vehicle + """ + kinematics_state = self.client.call("simGetGroundTruthKinematics", vehicle_name) + return KinematicsState.from_msgpack(kinematics_state)
+ + + simGetGroundTruthKinematics.__annotations__ = {"return": KinematicsState} + +
+[docs] + def simSetKinematics(self, state, ignore_collision, vehicle_name=""): + """ + Set the kinematics state of the vehicle + + If you don't want to change position (or orientation) then just set components of position (or orientation) to floating point nan values + + Args: + state (KinematicsState): Desired Pose pf the vehicle + ignore_collision (bool): Whether to ignore any collision or not + vehicle_name (str, optional): Name of the vehicle to move + """ + self.client.call("simSetKinematics", state, ignore_collision, vehicle_name)
+ + +
+[docs] + def simGetGroundTruthEnvironment(self, vehicle_name=""): + """ + Get ground truth environment state + + The position inside the returned EnvironmentState is in the frame of the vehicle's starting point + + Args: + vehicle_name (str, optional): Name of the vehicle + + Returns: + EnvironmentState: Ground truth environment state + """ + env_state = self.client.call("simGetGroundTruthEnvironment", vehicle_name) + return EnvironmentState.from_msgpack(env_state)
+ + + simGetGroundTruthEnvironment.__annotations__ = {"return": EnvironmentState} + + # sensor APIs +
+[docs] + def getImuData(self, imu_name="", vehicle_name=""): + """ + Args: + imu_name (str, optional): Name of IMU to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + ImuData: + """ + return ImuData.from_msgpack( + self.client.call("getImuData", imu_name, vehicle_name) + )
+ + +
+[docs] + def getBarometerData(self, barometer_name="", vehicle_name=""): + """ + Args: + barometer_name (str, optional): Name of Barometer to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + BarometerData: + """ + return BarometerData.from_msgpack( + self.client.call("getBarometerData", barometer_name, vehicle_name) + )
+ + +
+[docs] + def getMagnetometerData(self, magnetometer_name="", vehicle_name=""): + """ + Args: + magnetometer_name (str, optional): Name of Magnetometer to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + MagnetometerData: + """ + return MagnetometerData.from_msgpack( + self.client.call("getMagnetometerData", magnetometer_name, vehicle_name) + )
+ + +
+[docs] + def getGpsData(self, gps_name="", vehicle_name=""): + """ + Args: + gps_name (str, optional): Name of GPS to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + GpsData: + """ + return GpsData.from_msgpack( + self.client.call("getGpsData", gps_name, vehicle_name) + )
+ + +
+[docs] + def getDistanceSensorData(self, distance_sensor_name="", vehicle_name=""): + """ + Args: + distance_sensor_name (str, optional): Name of Distance Sensor to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + DistanceSensorData: + """ + return DistanceSensorData.from_msgpack( + self.client.call( + "getDistanceSensorData", distance_sensor_name, vehicle_name + ) + )
+ + +
+[docs] + def getLidarData(self, lidar_name="", vehicle_name=""): + """ + Args: + lidar_name (str, optional): Name of Lidar to get data from, specified in settings.json + vehicle_name (str, optional): Name of vehicle to which the sensor corresponds to + + Returns: + LidarData: + """ + return LidarData.from_msgpack( + self.client.call("getLidarData", lidar_name, vehicle_name) + )
+ + +
+[docs] + def simGetLidarSegmentation(self, lidar_name="", vehicle_name=""): + """ + NOTE: Deprecated API, use `getLidarData()` API instead + Returns Segmentation ID of each point's collided object in the last Lidar update + + Args: + lidar_name (str, optional): Name of Lidar sensor + vehicle_name (str, optional): Name of the vehicle wth the sensor + + Returns: + list[int]: Segmentation IDs of the objects + """ + logging.warning( + "simGetLidarSegmentation API is deprecated, use getLidarData() API instead" + ) + return self.getLidarData(lidar_name, vehicle_name).segmentation
+ + + # Plotting APIs +
+[docs] + def simFlushPersistentMarkers(self): + """ + Clear any persistent markers - those plotted with setting `is_persistent=True` in the APIs below + """ + self.client.call("simFlushPersistentMarkers")
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + def cancelLastTask(self, vehicle_name=""): + """ + Cancel previous Async task + + Args: + vehicle_name (str, optional): Name of the vehicle + """ + self.client.call("cancelLastTask", vehicle_name)
+ + + # Recording APIs +
+[docs] + def startRecording(self): + """ + Start Recording + + Recording will be done according to the settings + """ + self.client.call("startRecording")
+ + +
+[docs] + def stopRecording(self): + """ + Stop Recording + """ + self.client.call("stopRecording")
+ + +
+[docs] + def isRecording(self): + """ + Whether Recording is running or not + + Returns: + bool: True if Recording, else False + """ + return self.client.call("isRecording")
+ + +
+[docs] + def simSetWind(self, wind): + """ + Set simulated wind, in World frame, NED direction, m/s + + Args: + wind (Vector3r): Wind, in World frame, NED direction, in m/s + """ + self.client.call("simSetWind", wind)
+ + +
+[docs] + def simCreateVoxelGrid(self, position, x, y, z, res, of): + """ + Construct and save a binvox-formatted voxel grid of environment + + Args: + position (Vector3r): Position around which voxel grid is centered in m + x, y, z (int): Size of each voxel grid dimension in m + res (float): Resolution of voxel grid in m + of (str): Name of output file to save voxel grid as + + Returns: + bool: True if output written to file successfully, else False + """ + return self.client.call("simCreateVoxelGrid", position, x, y, z, res, of)
+ + + # Add new vehicle via RPC +
+[docs] + def simAddVehicle(self, vehicle_name, vehicle_type, pose, pawn_path=""): + """ + Create vehicle at runtime + + Args: + vehicle_name (str): Name of the vehicle being created + vehicle_type (str): Type of vehicle, e.g. "simpleflight" + pose (Pose): Initial pose of the vehicle + pawn_path (str, optional): Vehicle blueprint path, default empty wbich uses the default blueprint for the vehicle type + + Returns: + bool: Whether vehicle was created + """ + return self.client.call( + "simAddVehicle", vehicle_name, vehicle_type, pose, pawn_path + )
+ + +
+[docs] + def listVehicles(self): + """ + Lists the names of current vehicles + + Returns: + list[str]: List containing names of all vehicles + """ + return self.client.call("listVehicles")
+ + +
+[docs] + def getSettingsString(self): + """ + Fetch the settings text being used by AutonomySim + + Returns: + str: Settings text in JSON format + """ + return self.client.call("getSettingsString")
+ + +
+[docs] + def simSetExtForce(self, ext_force): + """ + Set arbitrary external forces, in World frame, NED direction. Can be used + for implementing simple payloads. + + Args: + ext_force (Vector3r): Force, in World frame, NED direction, in N + """ + self.client.call("simSetExtForce", ext_force)
+
+ + + +# ----------------------------------- Multirotor APIs --------------------------------------------- +
+[docs] +class MultirotorClient(VehicleClient, object): + def __init__(self, ip="", port=41451, timeout_value=3600): + super(MultirotorClient, self).__init__(ip, port, timeout_value) + +
+[docs] + def takeoffAsync(self, timeout_sec=20, vehicle_name=""): + """ + Takeoff vehicle to 3m above ground. Vehicle should not be moving when this API is used + + Args: + timeout_sec (int, optional): Timeout for the vehicle to reach desired altitude + vehicle_name (str, optional): Name of the vehicle 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("takeoff", timeout_sec, vehicle_name)
+ + +
+[docs] + def landAsync(self, timeout_sec=60, vehicle_name=""): + """ + Land the vehicle + + Args: + timeout_sec (int, optional): Timeout for the vehicle to land + vehicle_name (str, optional): Name of the vehicle 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("land", timeout_sec, vehicle_name)
+ + +
+[docs] + def goHomeAsync(self, timeout_sec=3e38, vehicle_name=""): + """ + Return vehicle to Home i.e. Launch location + + Args: + timeout_sec (int, optional): Timeout for the vehicle to reach desired altitude + vehicle_name (str, optional): Name of the vehicle 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("goHome", timeout_sec, vehicle_name)
+ + + # APIs for control +
+[docs] + def moveByVelocityBodyFrameAsync( + self, + vx, + vy, + vz, + duration, + drivetrain=DrivetrainType.MaxDegreeOfFreedom, + yaw_mode=YawMode(), + vehicle_name="", + ): + """ + Args: + vx (float): desired velocity in the X axis of the vehicle's local NED frame. + vy (float): desired velocity in the Y axis of the vehicle's local NED frame. + vz (float): desired velocity in the Z axis of the vehicle's local NED frame. + duration (float): Desired amount of time (seconds), to send this command for + drivetrain=0 (DrivetrainType, optional): + yaw_mode=<YawMode> (YawMode, optional): + 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( + "moveByVelocityBodyFrame", + vx, + vy, + vz, + duration, + drivetrain, + yaw_mode, + vehicle_name, + )
+ + +
+[docs] + def moveByVelocityZBodyFrameAsync( + self, + vx, + vy, + z, + duration, + drivetrain=DrivetrainType.MaxDegreeOfFreedom, + yaw_mode=YawMode(), + vehicle_name="", + ): + """ + Args: + vx (float): desired velocity in the X axis of the vehicle's local NED frame + vy (float): desired velocity in the Y axis of the vehicle's local NED frame + z (float): desired Z value (in local NED frame of the vehicle) + duration (float): Desired amount of time (seconds), to send this command for + drivetrain=0 (DrivetrainType, optional): + yaw_mode=<YawMode> (YawMode, optional): + 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( + "moveByVelocityZBodyFrame", + vx, + vy, + z, + duration, + drivetrain, + yaw_mode, + vehicle_name, + )
+ + +
+[docs] + def moveByAngleZAsync(self, pitch, roll, z, yaw, duration, vehicle_name=""): + logging.warning( + "moveByAngleZAsync API is deprecated, use moveByRollPitchYawZAsync() API instead" + ) + return self.client.call_async( + "moveByRollPitchYawZ", roll, -pitch, -yaw, z, duration, vehicle_name + )
+ + +
+[docs] + def moveByAngleThrottleAsync( + self, pitch, roll, throttle, yaw_rate, duration, vehicle_name="" + ): + logging.warning( + "moveByAngleThrottleAsync API is deprecated, use moveByRollPitchYawrateThrottleAsync() API instead" + ) + return self.client.call_async( + "moveByRollPitchYawrateThrottle", + roll, + -pitch, + -yaw_rate, + throttle, + duration, + vehicle_name, + )
+ + +
+[docs] + def moveByVelocityAsync( + self, + vx, + vy, + vz, + duration, + drivetrain=DrivetrainType.MaxDegreeOfFreedom, + yaw_mode=YawMode(), + vehicle_name="", + ): + """ + Args: + vx (float): desired velocity in world (NED) X axis + vy (float): desired velocity in world (NED) Y axis + vz (float): desired velocity in world (NED) Z axis + duration (float): Desired amount of time (seconds), to send this command for + drivetrain=0 (DrivetrainType, optional): + yaw_mode=<YawMode> (YawMode, optional): + 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( + "moveByVelocity", vx, vy, vz, duration, drivetrain, yaw_mode, vehicle_name + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + def moveOnPathAsync( + self, + path, + velocity, + timeout_sec=3e38, + 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, + )
+ + +
+[docs] + def moveToPositionAsync( + self, + x, + y, + z, + velocity, + timeout_sec=3e38, + 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, + )
+ + +
+[docs] + def moveToGPSAsync( + self, + latitude, + longitude, + altitude, + velocity, + timeout_sec=3e38, + drivetrain=DrivetrainType.MaxDegreeOfFreedom, + yaw_mode=YawMode(), + lookahead=-1, + adaptive_lookahead=1, + vehicle_name="", + ): + return self.client.call_async( + "moveToGPS", + latitude, + longitude, + altitude, + velocity, + timeout_sec, + drivetrain, + yaw_mode, + lookahead, + adaptive_lookahead, + vehicle_name, + )
+ + +
+[docs] + def moveToZAsync( + self, + z, + velocity, + timeout_sec=3e38, + 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, + )
+ + +
+[docs] + 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 setup 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. + + Args: + vx_max (float): max velocity allowed in x direction + vy_max (float): max velocity allowed in y direction + z_min (float): min z allowed for vehicle position + duration (float): after this duration vehicle would switch back to non-manual mode + drivetrain=0 (DrivetrainType): when ForwardOnly, vehicle rotates itself so that its front is always facing the direction of travel. If MaxDegreeOfFreedom then it doesn't do that and instead does crab-like movement + yaw_mode=<YawMode> (YawMode): Specifies if vehicle should face at given angle (is_rate=False) or should be rotating around its axis at given rate (is_rate=True) + 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( + "moveByManual", + vx_max, + vy_max, + z_min, + duration, + drivetrain, + yaw_mode, + vehicle_name, + )
+ + +
+[docs] + def rotateToYawAsync(self, yaw, timeout_sec=3e38, margin=5, vehicle_name=""): + return self.client.call_async( + "rotateToYaw", yaw, timeout_sec, margin, vehicle_name + )
+ + +
+[docs] + def rotateByYawRateAsync(self, yaw_rate, duration, vehicle_name=""): + return self.client.call_async( + "rotateByYawRate", yaw_rate, duration, vehicle_name + )
+ + +
+[docs] + def hoverAsync(self, vehicle_name=""): + return self.client.call_async("hover", vehicle_name)
+ + +
+[docs] + def moveByRC(self, rcdata=RCData(), vehicle_name=""): + return self.client.call("moveByRC", rcdata, vehicle_name)
+ + + # low - level control API +
+[docs] + 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, + )
+ + +
+[docs] + 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 + )
+ + +
+[docs] + 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 **degrees** when using PX4 and in **radians** when using SimpleFlight, 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. + pitch (float): Desired pitch angle. + yaw (float): Desired yaw angle. + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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, + )
+ + +
+[docs] + 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> (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,)), + )
+ + +
+[docs] + 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 AutonomySim 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 AutonomySim values. + + Args: + angle_level_gains=<AngleLevelControllerGains> (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,)), + )
+ + +
+[docs] + 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 AutonomySim values. + + Args: + velocity_gains=<VelocityControllerGains> (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,)) + )
+ + +
+[docs] + 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> (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 +
+[docs] + def getMultirotorState(self, vehicle_name=""): + """ + The position inside the returned MultirotorState is in the frame of the vehicle's starting point + + Args: + vehicle_name (str, optional): Vehicle to get the state of + + Returns: + MultirotorState: + """ + return MultirotorState.from_msgpack( + self.client.call("getMultirotorState", vehicle_name) + )
+ + + getMultirotorState.__annotations__ = {"return": MultirotorState} + + # query rotor states +
+[docs] + def getRotorStates(self, vehicle_name=""): + """ + Used to obtain the current state of all a multirotor's rotors. The state includes the speeds, + thrusts and torques for all rotors. + + Args: + vehicle_name (str, optional): Vehicle to get the rotor state of + + Returns: + RotorStates: Containing a timestamp and the speed, thrust and torque of all rotors. + """ + return RotorStates.from_msgpack( + self.client.call("getRotorStates", vehicle_name) + )
+ + + getRotorStates.__annotations__ = {"return": RotorStates}
+ + + +# ----------------------------------- Car APIs --------------------------------------------- +
+[docs] +class CarClient(VehicleClient, object): + def __init__(self, ip="", port=41451, timeout_value=3600): + super(CarClient, self).__init__(ip, port, timeout_value) + +
+[docs] + 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)
+ + +
+[docs] + 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)
+ + +
+[docs] + 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)
+
+ +
+ + + + + + +
+
+ + + + +
+ + + +
+ +
+ + + + +
+ +
+
+
+
+ + + + + + + + + \ No newline at end of file diff --git a/api/python/html/_modules/autonomysim/types.html b/api/python/html/_modules/autonomysim/types.html index e8f8a3b3..07352972 100644 --- a/api/python/html/_modules/autonomysim/types.html +++ b/api/python/html/_modules/autonomysim/types.html @@ -263,8 +263,8 @@
  • - - autonomysim package + + autonomysim
  • @@ -298,9 +298,9 @@

    Source code for autonomysim.types

    -import msgpackrpc  # install as admin: pip install msgpack-rpc-python
    -import numpy as np  # pip install numpy
    -import math
    +import math
    +import numpy as np
    +# import msgpackrpc
     
     
     
    diff --git a/api/python/html/_modules/autonomysim/unreal/commands.html b/api/python/html/_modules/autonomysim/unreal/commands.html new file mode 100644 index 00000000..e730a179 --- /dev/null +++ b/api/python/html/_modules/autonomysim/unreal/commands.html @@ -0,0 +1,421 @@ + + + + + + + + + + + + + + + + autonomysim.unreal.commands - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    Source code for autonomysim.unreal.commands

    +import time
    +
    +
    +
    +[docs] +def RunConsoleCmd(client, cmd): + client.simRunConsoleCommand(cmd) + print(f"Running Unreal Console cmd '{cmd}' and sleeping for 1 second") + time.sleep(1.0)
    + + + +
    +[docs] +def RunCmdList(client): + RunConsoleCmd(client, "stat fps") + RunConsoleCmd(client, "stat unit") + RunConsoleCmd(client, "stat unitGraph") + RunConsoleCmd(client, "show COLLISION") + RunConsoleCmd(client, "show CollisionVisibility") + RunConsoleCmd(client, "stat game") + RunConsoleCmd(client, "show COLLISION") + RunConsoleCmd(client, "show CollisionVisibility") + RunConsoleCmd(client, "stat game") + RunConsoleCmd(client, "stat unitGraph") + RunConsoleCmd(client, "stat unit") + RunConsoleCmd(client, "stat fps")
    + +
    + + + + + + +
    +
    + + + + +
    + + + +
    + +
    + + + + +
    + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/_modules/autonomysim/utils.html b/api/python/html/_modules/autonomysim/utils.html index f175a902..155e1d39 100644 --- a/api/python/html/_modules/autonomysim/utils.html +++ b/api/python/html/_modules/autonomysim/utils.html @@ -263,8 +263,8 @@
  • - - autonomysim package + + autonomysim
  • @@ -298,141 +298,122 @@

    Source code for autonomysim.utils

    -from .types import *
    -
    -import numpy as np #pip install numpy
    -import math
    -import time
    +import os
     import sys
    -import os
     import inspect
    -import types
    -import re
     import logging
     
    -
    -[docs] -def string_to_uint8_array(bstr): - return np.fromstring(bstr, np.uint8)
    +description = """ +Utilities +""" - -
    -[docs] -def string_to_float_array(bstr): - return np.fromstring(bstr, np.float32)
    - -
    -[docs] -def list_to_2d_float_array(flst, width, height): - return np.reshape(np.asarray(flst, np.float32), (height, width))
    - - -
    -[docs] -def get_pfm_array(response): - return list_to_2d_float_array(response.image_data_float, response.width, response.height)
    +
    +[docs] +class SetupPath: + """ + Import this module to automatically setup path to local AutonomySim module. + This module first tries to see if AutonomySim module is installed via `pip`. + If it does, we don't do anything else. Else, we look up grand-parent folder to + see if it has AutonomySim folder and if it does then we add that in the `sys.path`. + """ -
    -[docs] -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))]
    + def __init__(self) -> None: + self.addAutonomySimModulePath() + +
    +[docs] + @staticmethod + def getDirLevels(path): + path_norm = os.path.normpath(path) + return len(path_norm.split(os.sep))
    + + +
    +[docs] + @staticmethod + def getCurrentPath(): + cur_filepath = os.path.abspath(inspect.getfile(inspect.currentframe())) + return os.path.dirname(cur_filepath)
    + + +
    +[docs] + @staticmethod + def getGrandParentDir(): + cur_path = SetupPath.getCurrentPath() + if SetupPath.getDirLevels(cur_path) >= 2: + return os.path.dirname(os.path.dirname(cur_path)) + return ""
    + + +
    +[docs] + @staticmethod + def getParentDir(): + cur_path = SetupPath.getCurrentPath() + if SetupPath.getDirLevels(cur_path) >= 1: + return os.path.dirname(cur_path) + return ""
    + + +
    +[docs] + @staticmethod + def addAutonomySimModulePath(): + # if AutonomySim module is installed then don't do anything else + # import pkgutil + # autonomysim_loader = pkgutil.find_loader('AutonomySim') + # if autonomysim_loader is not None: + # return + + parent = SetupPath.getParentDir() + if parent != "": + autonomysim_path = os.path.join(parent, "AutonomySim") + client_path = os.path.join(autonomysim_path, "client.py") + if os.path.exists(client_path): + sys.path.insert(0, parent) + else: + logging.warning( + "AutonomySim module not found in parent folder. Using installed package (pip install AutonomySim)." + )
    +
    -
    -[docs] -def to_dict(obj): - return dict([attr, getattr(obj, attr)] for attr in get_public_fields(obj))
    - -
    -[docs] -def to_str(obj): - return str(to_dict(obj))
    +
    +[docs] +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) + ) + ]
    -
    -[docs] -def write_file(filename, bstr): - """ - Write binary data to file. - Used for writing compressed PNG images - """ - with open(filename, 'wb') as afile: - afile.write(bstr)
    - - -# helper method for converting getOrientation to roll/pitch/yaw -# https:#en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles - -
    -[docs] -def to_eularian_angles(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)
    - - -
    -[docs] -def to_quaternion(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
    -
    -[docs] -def wait_key(message = ''): - ''' Wait for a key press on the console and return it. ''' - if message != '': - print (message) +[docs] +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': + if os.name == "nt": import msvcrt + result = msvcrt.getch() else: import termios - fd = sys.stdin.fileno() + fd = sys.stdin.fileno() oldterm = termios.tcgetattr(fd) newattr = termios.tcgetattr(fd) newattr[3] = newattr[3] & ~termios.ICANON & ~termios.ECHO @@ -447,94 +428,46 @@

    Source code for autonomysim.utils

     
         return result
    - -
    -[docs] -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. - file.close() - - return data, scale
    - -
    -[docs] -def write_pfm(file, image, scale=1): - """ Write a pfm file """ - file = open(file, 'wb') - color = None +
    +[docs] +def generate_color_palette(numPixelsWide, outputFile): + import random + import numpy as np + import cv2 - if image.dtype.name != 'float32': - raise Exception('Image dtype must be float32.') + random.seed(42) - 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: # grayscale - 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')) + palette = np.zeros((1, 256 * numPixelsWide, 3)) + possibilities = [list(range(256)), list(range(256)), list(range(256))] - endian = image.dtype.byteorder + colors = [[0] * 3 for i in range(256)] + choice = 0 + j = 0 + for i in range(3): + palette[0, j * numPixelsWide : (j + 1) * numPixelsWide, i] = choice + colors[j][i] = choice - if endian == '<' or endian == '=' and sys.byteorder == 'little': - scale = -scale + for i in range(3): + for j in range(1, 255): + choice = random.sample(possibilities[i], 1)[0] + possibilities[i].remove(choice) + palette[0, j * numPixelsWide : (j + 1) * numPixelsWide, i] = choice + colors[j][i] = choice - temp_str = '%f\n' % scale - file.write(temp_str.encode('utf-8')) + choice = 255 + j = 255 + for i in range(3): + palette[0, j * numPixelsWide : (j + 1) * numPixelsWide, i] = choice + colors[j][i] = choice - image.tofile(file)
    - - -
    -[docs] -def write_png(filename, image): - """ image must be numpy array H X W X channels """ - import cv2 # pip install opencv-python + cv2.imwrite(outputFile, palette, [cv2.IMWRITE_PNG_COMPRESSION, 0]) - ret = cv2.imwrite(filename, image) - if not ret: - logging.error(f"Writing PNG file {filename} failed")
    + rgb_file = open("rgbs.txt", "w") + for j in range(256): + rgb_file.write("%d\t%s\n" % (j, str(list(reversed(colors[j]))))) + rgb_file.close()
    diff --git a/api/python/html/_modules/autonomysim/utils/convs.html b/api/python/html/_modules/autonomysim/utils/convs.html new file mode 100644 index 00000000..b9b3c4c5 --- /dev/null +++ b/api/python/html/_modules/autonomysim/utils/convs.html @@ -0,0 +1,494 @@ + + + + + + + + + + + + + + + + autonomysim.utils.convs - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    Source code for autonomysim.utils.convs

    +import math
    +import numpy as np
    +# import sys
    +# import os
    +# import inspect
    +# import re
    +# import logging
    +# import types
    +# import time
    +
    +from autonomysim.types import Quaternionr
    +from autonomysim.utils import get_public_fields
    +
    +
    +
    +[docs] +def string_to_uint8_array(bstr): + return np.fromstring(bstr, np.uint8)
    + + + +
    +[docs] +def string_to_float_array(bstr): + return np.fromstring(bstr, np.float32)
    + + + +
    +[docs] +def list_to_2d_float_array(flst, width, height): + return np.reshape(np.asarray(flst, np.float32), (height, width))
    + + + +
    +[docs] +def to_dict(obj): + return dict([attr, getattr(obj, attr)] for attr in get_public_fields(obj))
    + + + +
    +[docs] +def to_str(obj): + return str(to_dict(obj))
    + + + +# helper method for converting getOrientation to roll/pitch/yaw +# https:#en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + + +
    +[docs] +def to_eularian_angles(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)
    + + + +
    +[docs] +def to_quaternion(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
    + +
    + + + + + + +
    +
    + + + + +
    + + + +
    + +
    + + + + +
    + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/_modules/autonomysim/utils/io.html b/api/python/html/_modules/autonomysim/utils/io.html new file mode 100644 index 00000000..67b50353 --- /dev/null +++ b/api/python/html/_modules/autonomysim/utils/io.html @@ -0,0 +1,522 @@ + + + + + + + + + + + + + + + + autonomysim.utils.io - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    Source code for autonomysim.utils.io

    +import numpy as np
    +import re
    +import sys
    +import logging
    +# import matplotlib.pyplot as plt
    +# import pdb
    +
    +from autonomysim.utils.convs import list_to_2d_float_array
    +
    +
    +
    +[docs] +def write_file(filename, bstr): + """ + Write binary data to file. + Used for writing compressed PNG images + """ + with open(filename, "wb") as fh: + fh.write(bstr)
    + + + +
    +[docs] +def write_png(filename, image): + """image must be numpy array H X W X channels""" + import cv2 + + ret = cv2.imwrite(filename, image) + if not ret: + logging.error(f"Writing PNG file {filename} failed")
    + + + +
    +[docs] +def get_pfm_array(response): + return list_to_2d_float_array( + response.image_data_float, response.width, response.height + )
    + + + +
    +[docs] +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.") + + pattern = r"^(\d+)\s(\d+)\s$" + temp_str = str(bytes.decode(file.readline(), encoding="utf-8")) + dim_match = re.match(pattern, temp_str) + if dim_match: + width, height = map(int, dim_match.groups()) + else: + temp_str += str(bytes.decode(file.readline(), encoding="utf-8")) + dim_match = re.match(pattern, temp_str) + if dim_match: + width, height = map(int, dim_match.groups()) + else: + raise Exception("Malformed PFM header: width, height cannot be found") + + 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. + file.close() + + return data, scale
    + + + +
    +[docs] +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.") + + 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(bytes("PF\n", "UTF-8") if color else bytes("Pf\n", "UTF-8")) + temp_str = "%d %d\n" % (image.shape[1], image.shape[0]) + file.write(bytes(temp_str, "UTF-8")) + + endian = image.dtype.byteorder + + if endian == "<" or endian == "=" and sys.byteorder == "little": + scale = -scale + + temp_str = "%f\n" % scale + file.write(bytes(temp_str, "UTF-8")) + + image.tofile(file)
    + +
    + + + + + + +
    +
    + + + + +
    + + + +
    + +
    + + + + +
    + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/_modules/index.html b/api/python/html/_modules/index.html index ca485e72..ab9c383f 100644 --- a/api/python/html/_modules/index.html +++ b/api/python/html/_modules/index.html @@ -263,8 +263,8 @@
  • - - autonomysim package + + autonomysim
  • @@ -298,10 +298,13 @@

    All modules for which code is available

    - diff --git a/api/python/html/_sources/api/autonomysim.ai.imitation.rst.txt b/api/python/html/_sources/api/autonomysim.ai.imitation.rst.txt new file mode 100644 index 00000000..94eddb81 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.ai.imitation.rst.txt @@ -0,0 +1,45 @@ +autonomysim.ai.imitation package +================================ + +Submodules +---------- + +autonomysim.ai.imitation.agents module +-------------------------------------- + +.. automodule:: autonomysim.ai.imitation.agents + :members: + :undoc-members: + :show-inheritance: + +autonomysim.ai.imitation.generators module +------------------------------------------ + +.. automodule:: autonomysim.ai.imitation.generators + :members: + :undoc-members: + :show-inheritance: + +autonomysim.ai.imitation.preprocessors module +--------------------------------------------- + +.. automodule:: autonomysim.ai.imitation.preprocessors + :members: + :undoc-members: + :show-inheritance: + +autonomysim.ai.imitation.trainers module +---------------------------------------- + +.. automodule:: autonomysim.ai.imitation.trainers + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.ai.imitation + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.ai.reinforcement.rst.txt b/api/python/html/_sources/api/autonomysim.ai.reinforcement.rst.txt new file mode 100644 index 00000000..44a086c4 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.ai.reinforcement.rst.txt @@ -0,0 +1,10 @@ +autonomysim.ai.reinforcement package +==================================== + +Module contents +--------------- + +.. automodule:: autonomysim.ai.reinforcement + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.ai.rst.txt b/api/python/html/_sources/api/autonomysim.ai.rst.txt new file mode 100644 index 00000000..4e74b0f1 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.ai.rst.txt @@ -0,0 +1,20 @@ +autonomysim.ai package +====================== + +Subpackages +----------- + +.. toctree:: + :maxdepth: 4 + + autonomysim.ai.imitation + autonomysim.ai.reinforcement + autonomysim.ai.vision + +Module contents +--------------- + +.. automodule:: autonomysim.ai + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.ai.vision.rst.txt b/api/python/html/_sources/api/autonomysim.ai.vision.rst.txt new file mode 100644 index 00000000..8f28a15c --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.ai.vision.rst.txt @@ -0,0 +1,29 @@ +autonomysim.ai.vision package +============================= + +Submodules +---------- + +autonomysim.ai.vision.benchmarks module +--------------------------------------- + +.. automodule:: autonomysim.ai.vision.benchmarks + :members: + :undoc-members: + :show-inheritance: + +autonomysim.ai.vision.navigation module +--------------------------------------- + +.. automodule:: autonomysim.ai.vision.navigation + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.ai.vision + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.gym.envs.rst.txt b/api/python/html/_sources/api/autonomysim.gym.envs.rst.txt new file mode 100644 index 00000000..aa339940 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.gym.envs.rst.txt @@ -0,0 +1,37 @@ +autonomysim.gym.envs package +============================ + +Submodules +---------- + +autonomysim.gym.envs.autonomysim\_env module +-------------------------------------------- + +.. automodule:: autonomysim.gym.envs.autonomysim_env + :members: + :undoc-members: + :show-inheritance: + +autonomysim.gym.envs.car\_env module +------------------------------------ + +.. automodule:: autonomysim.gym.envs.car_env + :members: + :undoc-members: + :show-inheritance: + +autonomysim.gym.envs.drone\_env module +-------------------------------------- + +.. automodule:: autonomysim.gym.envs.drone_env + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.gym.envs + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.gym.rst.txt b/api/python/html/_sources/api/autonomysim.gym.rst.txt new file mode 100644 index 00000000..152fcb98 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.gym.rst.txt @@ -0,0 +1,18 @@ +autonomysim.gym package +======================= + +Subpackages +----------- + +.. toctree:: + :maxdepth: 4 + + autonomysim.gym.envs + +Module contents +--------------- + +.. automodule:: autonomysim.gym + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.rst.txt b/api/python/html/_sources/api/autonomysim.rst.txt index 39e0be5d..0562a564 100644 --- a/api/python/html/_sources/api/autonomysim.rst.txt +++ b/api/python/html/_sources/api/autonomysim.rst.txt @@ -1,21 +1,25 @@ autonomysim package =================== -Submodules ----------- +Subpackages +----------- -autonomysim.client module -------------------------- +.. toctree:: + :maxdepth: 4 -.. automodule:: autonomysim.client - :members: - :undoc-members: - :show-inheritance: + autonomysim.ai + autonomysim.gym + autonomysim.sensors + autonomysim.unreal + autonomysim.utils + +Submodules +---------- -autonomysim.pfm module ----------------------- +autonomysim.clients module +-------------------------- -.. automodule:: autonomysim.pfm +.. automodule:: autonomysim.clients :members: :undoc-members: :show-inheritance: @@ -28,14 +32,6 @@ autonomysim.types module :undoc-members: :show-inheritance: -autonomysim.utils module ------------------------- - -.. automodule:: autonomysim.utils - :members: - :undoc-members: - :show-inheritance: - Module contents --------------- diff --git a/api/python/html/_sources/api/autonomysim.sensors.rst.txt b/api/python/html/_sources/api/autonomysim.sensors.rst.txt new file mode 100644 index 00000000..b02bf04f --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.sensors.rst.txt @@ -0,0 +1,37 @@ +autonomysim.sensors package +=========================== + +Submodules +---------- + +autonomysim.sensors.event\_camera module +---------------------------------------- + +.. automodule:: autonomysim.sensors.event_camera + :members: + :undoc-members: + :show-inheritance: + +autonomysim.sensors.kinect module +--------------------------------- + +.. automodule:: autonomysim.sensors.kinect + :members: + :undoc-members: + :show-inheritance: + +autonomysim.sensors.thermal\_camera module +------------------------------------------ + +.. automodule:: autonomysim.sensors.thermal_camera + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.sensors + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.unreal.rst.txt b/api/python/html/_sources/api/autonomysim.unreal.rst.txt new file mode 100644 index 00000000..40ae9cd7 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.unreal.rst.txt @@ -0,0 +1,21 @@ +autonomysim.unreal package +========================== + +Submodules +---------- + +autonomysim.unreal.commands module +---------------------------------- + +.. automodule:: autonomysim.unreal.commands + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.unreal + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.utils.io.rst.txt b/api/python/html/_sources/api/autonomysim.utils.io.rst.txt new file mode 100644 index 00000000..e268c7de --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.utils.io.rst.txt @@ -0,0 +1,21 @@ +autonomysim.utils.io package +============================ + +Submodules +---------- + +autonomysim.utils.io.audio module +--------------------------------- + +.. automodule:: autonomysim.utils.io.audio + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.utils.io + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/autonomysim.utils.rst.txt b/api/python/html/_sources/api/autonomysim.utils.rst.txt new file mode 100644 index 00000000..8084d296 --- /dev/null +++ b/api/python/html/_sources/api/autonomysim.utils.rst.txt @@ -0,0 +1,29 @@ +autonomysim.utils package +========================= + +Subpackages +----------- + +.. toctree:: + :maxdepth: 4 + + autonomysim.utils.io + +Submodules +---------- + +autonomysim.utils.convs module +------------------------------ + +.. automodule:: autonomysim.utils.convs + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: autonomysim.utils + :members: + :undoc-members: + :show-inheritance: diff --git a/api/python/html/_sources/api/modules.rst.txt b/api/python/html/_sources/api/modules.rst.txt new file mode 100644 index 00000000..50be1d04 --- /dev/null +++ b/api/python/html/_sources/api/modules.rst.txt @@ -0,0 +1,7 @@ +autonomysim +=========== + +.. toctree:: + :maxdepth: 4 + + autonomysim diff --git a/api/python/html/_sources/index.rst.txt b/api/python/html/_sources/index.rst.txt index 00145278..06967a42 100644 --- a/api/python/html/_sources/index.rst.txt +++ b/api/python/html/_sources/index.rst.txt @@ -6,15 +6,16 @@ AutonomySim =========== -This page documents `autonomysim`_, the Python package of `AutonomySim`_. +This page documents `autonomysim`_, the Python package of `Nervosys AutonomySim`_. -.. _`AutonomySim`: https://github.com/nervosys/AutonomySim +.. _`autonomysim`: https://pypi.org/project/autonomysim/ +.. _`Nervosys AutonomySim`: https://github.com/nervosys/AutonomySim .. toctree:: :maxdepth: 4 :caption: Contents: - api/autonomysim + api/modules Indices and Tables ================== diff --git a/api/python/html/api/autonomysim.ai.html b/api/python/html/api/autonomysim.ai.html new file mode 100644 index 00000000..11549939 --- /dev/null +++ b/api/python/html/api/autonomysim.ai.html @@ -0,0 +1,709 @@ + + + + + + + + + + + + + + + + autonomysim.ai package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + + + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.ai.imitation.html b/api/python/html/api/autonomysim.ai.imitation.html new file mode 100644 index 00000000..e2c7d5df --- /dev/null +++ b/api/python/html/api/autonomysim.ai.imitation.html @@ -0,0 +1,800 @@ + + + + + + + + + + + + + + + + autonomysim.ai.imitation package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.ai.imitation package

    +

    Submodules

    +

    autonomysim.ai.imitation.agents module

    +

    autonomysim.ai.imitation.generators module

    +

    autonomysim.ai.imitation.preprocessors module

    +

    autonomysim.ai.imitation.trainers module

    +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.ai.reinforcement.html b/api/python/html/api/autonomysim.ai.reinforcement.html new file mode 100644 index 00000000..933f9b42 --- /dev/null +++ b/api/python/html/api/autonomysim.ai.reinforcement.html @@ -0,0 +1,760 @@ + + + + + + + + + + + + + + + + autonomysim.ai.reinforcement package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.ai.reinforcement package

    +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.ai.vision.html b/api/python/html/api/autonomysim.ai.vision.html new file mode 100644 index 00000000..e40b7ec1 --- /dev/null +++ b/api/python/html/api/autonomysim.ai.vision.html @@ -0,0 +1,784 @@ + + + + + + + + + + + + + + + + autonomysim.ai.vision package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.ai.vision package

    +

    Submodules

    +

    autonomysim.ai.vision.benchmarks module

    +

    autonomysim.ai.vision.navigation module

    +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.gym.envs.html b/api/python/html/api/autonomysim.gym.envs.html new file mode 100644 index 00000000..9935a830 --- /dev/null +++ b/api/python/html/api/autonomysim.gym.envs.html @@ -0,0 +1,762 @@ + + + + + + + + + + + + + + + + autonomysim.gym.envs package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.gym.envs package

    +

    Submodules

    +

    autonomysim.gym.envs.autonomysim_env module

    +

    autonomysim.gym.envs.car_env module

    +

    autonomysim.gym.envs.drone_env module

    +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.gym.html b/api/python/html/api/autonomysim.gym.html new file mode 100644 index 00000000..c5a554d3 --- /dev/null +++ b/api/python/html/api/autonomysim.gym.html @@ -0,0 +1,683 @@ + + + + + + + + + + + + + + + + autonomysim.gym package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + + + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.html b/api/python/html/api/autonomysim.html index 6645968d..684b259a 100644 --- a/api/python/html/api/autonomysim.html +++ b/api/python/html/api/autonomysim.html @@ -264,6 +264,38 @@ + + +
  • + + + + + + + + + +
  • + + + diff --git a/api/python/html/api/autonomysim.sensors.html b/api/python/html/api/autonomysim.sensors.html new file mode 100644 index 00000000..98467434 --- /dev/null +++ b/api/python/html/api/autonomysim.sensors.html @@ -0,0 +1,682 @@ + + + + + + + + + + + + + + + + autonomysim.sensors package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.sensors package

    +

    Submodules

    +

    autonomysim.sensors.event_camera module

    +

    autonomysim.sensors.kinect module

    +

    autonomysim.sensors.thermal_camera module

    +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.unreal.html b/api/python/html/api/autonomysim.unreal.html new file mode 100644 index 00000000..d260be2c --- /dev/null +++ b/api/python/html/api/autonomysim.unreal.html @@ -0,0 +1,696 @@ + + + + + + + + + + + + + + + + autonomysim.unreal package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.unreal package

    +

    Submodules

    +

    autonomysim.unreal.commands module

    +
    +
    +autonomysim.unreal.commands.RunCmdList(client)[source]
    +
    + +
    +
    +autonomysim.unreal.commands.RunConsoleCmd(client, cmd)[source]
    +
    + +

    Module contents

    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.utils.html b/api/python/html/api/autonomysim.utils.html new file mode 100644 index 00000000..f8c6261a --- /dev/null +++ b/api/python/html/api/autonomysim.utils.html @@ -0,0 +1,920 @@ + + + + + + + + + + + + + + + + autonomysim.utils package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.utils package

    +

    Subpackages

    + +

    Submodules

    +

    autonomysim.utils.convs module

    +
    +
    +autonomysim.utils.convs.list_to_2d_float_array(flst, width, height)[source]
    +
    + +
    +
    +autonomysim.utils.convs.string_to_float_array(bstr)[source]
    +
    + +
    +
    +autonomysim.utils.convs.string_to_uint8_array(bstr)[source]
    +
    + +
    +
    +autonomysim.utils.convs.to_dict(obj)[source]
    +
    + +
    +
    +autonomysim.utils.convs.to_eularian_angles(q)[source]
    +
    + +
    +
    +autonomysim.utils.convs.to_quaternion(pitch, roll, yaw)[source]
    +
    + +
    +
    +autonomysim.utils.convs.to_str(obj)[source]
    +
    + +

    Module contents

    +
    +
    +class autonomysim.utils.SetupPath[source]
    +

    Bases: object

    +

    Import this module to automatically setup path to local AutonomySim module.

    +

    This module first tries to see if AutonomySim module is installed via pip. +If it does, we don’t do anything else. Else, we look up grand-parent folder to +see if it has AutonomySim folder and if it does then we add that in the sys.path.

    +
    +
    +static addAutonomySimModulePath()[source]
    +
    + +
    +
    +static getCurrentPath()[source]
    +
    + +
    +
    +static getDirLevels(path)[source]
    +
    + +
    +
    +static getGrandParentDir()[source]
    +
    + +
    +
    +static getParentDir()[source]
    +
    + +
    + +
    +
    +autonomysim.utils.generate_color_palette(numPixelsWide, outputFile)[source]
    +
    + +
    +
    +autonomysim.utils.get_public_fields(obj)[source]
    +
    + +
    +
    +autonomysim.utils.wait_key(message='')[source]
    +

    Wait for a key press on the console and return it.

    +
    + + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/autonomysim.utils.io.html b/api/python/html/api/autonomysim.utils.io.html new file mode 100644 index 00000000..02b1d3ad --- /dev/null +++ b/api/python/html/api/autonomysim.utils.io.html @@ -0,0 +1,802 @@ + + + + + + + + + + + + + + + + autonomysim.utils.io package - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim.utils.io package

    +

    Submodules

    +

    autonomysim.utils.io.audio module

    +

    Module contents

    +
    +
    +autonomysim.utils.io.get_pfm_array(response)[source]
    +
    + +
    +
    +autonomysim.utils.io.read_pfm(file)[source]
    +

    Read a pfm file

    +
    + +
    +
    +autonomysim.utils.io.write_file(filename, bstr)[source]
    +

    Write binary data to file. +Used for writing compressed PNG images

    +
    + +
    +
    +autonomysim.utils.io.write_pfm(file, image, scale=1)[source]
    +

    Write a pfm file

    +
    + +
    +
    +autonomysim.utils.io.write_png(filename, image)[source]
    +

    image must be numpy array H X W X channels

    +
    + + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/api/modules.html b/api/python/html/api/modules.html new file mode 100644 index 00000000..4dbc748d --- /dev/null +++ b/api/python/html/api/modules.html @@ -0,0 +1,976 @@ + + + + + + + + + + + + + + + + autonomysim - AutonomySim Python API + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    + +
    +
    + +
    + + + + + + +
    + + +
    + +
    + + + + + + + + +
    +
    + + + +
    +
    +
    + + + + + + +
    +
    +
    + + + + +
    +
    + + + + + + + + +

    autonomysim

    +
    + +
    + + + + + + + +
    +
    + + + + +
    + + + +
    + + + +
    +
    +
    +
    + + + + + + + + + \ No newline at end of file diff --git a/api/python/html/genindex.html b/api/python/html/genindex.html index 34521af1..74e63c55 100644 --- a/api/python/html/genindex.html +++ b/api/python/html/genindex.html @@ -263,8 +263,8 @@
  • - - autonomysim package + + autonomysim
  • diff --git a/api/python/html/index.html b/api/python/html/index.html index c064dad1..b3ce5d32 100644 --- a/api/python/html/index.html +++ b/api/python/html/index.html @@ -268,8 +268,8 @@
  • - - autonomysim package + + autonomysim
  • @@ -303,495 +303,73 @@

    AutonomySim

    -

    This page documents autonomysim, the Python package of AutonomySim.

    +

    This page documents autonomysim, the Python package of Nervosys AutonomySim.

    Contents:

      -
    • autonomysim package
        -
      • Submodules
      • -
      • autonomysim.client module @@ -831,13 +409,13 @@

        Indices and Tables