__init__
RobotClient.__init__(
ip="",
port=41451,
timeout_value=3600,
run_in_background: bool = False,
)
Initializes the RobotClient
Arguments
IP address of the server, defaults to localhost
Port number of the server, defaults to 41451
Timeout value for the connection, defaults to 3600
Whether to run the client in background, defaults to False. When true, this client does not print info unless necessary.
Unless otherwise noted, methods accept an optional
robot_name argument. If left blank, AirGen targets the first robot defined in the session settings (alphabetical order).reset
RobotClient.reset()
Reset the robot to its original starting stateNote that you must call
enableApiControl and armDisarm again after the call to resetping
RobotClient.ping()
getClientVersion
RobotClient.getClientVersion()
No description provided!
getServerVersion
RobotClient.getServerVersion()
No description provided!
getMinRequiredServerVersion
RobotClient.getMinRequiredServerVersion()
No description provided!
getMinRequiredClientVersion
RobotClient.getMinRequiredClientVersion()
No description provided!
enableApiControl
RobotClient.enableApiControl(is_enabled, robot_name="")
isApiControlEnabled
RobotClient.isApiControlEnabled(robot_name="")
armDisarm
RobotClient.armDisarm(arm, robot_name="")
simPause
RobotClient.simPause(is_paused)
simIsPause
RobotClient.simIsPause()
simContinueForTime
RobotClient.simContinueForTime(seconds)
simContinueForFrames
RobotClient.simContinueForFrames(frames)
getHomeGeoPoint
RobotClient.getHomeGeoPoint(robot_name="")
confirmConnection
RobotClient.confirmConnection()
Checks state of connection every 1 sec and reports it in Console so user can see the progress for connection.
simSwapTextures
RobotClient.simSwapTextures(tags, tex_id=0, component_id=0, material_id=0)
Runtime Swap Texture API
Arguments
simSetObjectMaterial
RobotClient.simSetObjectMaterial(object_name, material_name, component_id=0)
simSetObjectMaterialFromTexture
RobotClient.simSetObjectMaterialFromTexture(
object_name, texture_path, component_id=0
)
simSetObjectMaterialFromTextureURL
RobotClient.simSetObjectMaterialFromTextureURL(
object_name, url, component_id=0
)
simSetTimeOfDay
RobotClient.simSetTimeOfDay(
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 environmentSun’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 usedArguments
True to enable time-of-day effect, False to reset the position to original
Date & Time in %Y-%m-%d %H:%M:%S format, e.g.
2018-02-12 15:20:00True to adjust for Daylight Savings Time
Run celestial clock faster or slower than simulation clock
Interval to update the Sun’s position
Whether or not to move the Sun
simEnableWeather
RobotClient.simEnableWeather(enable: bool)
simResetToAuthoredWeather
RobotClient.simResetToAuthoredWeather()
Reset all weather parameters to their original values as defined during scene authoring.
simSetWeatherParameter
RobotClient.simSetWeatherParameter(param:WeatherParameter, val:float)
simGetImage
RobotClient.simGetImage(camera_name, image_type, robot_name="", external=False, capture_3d=False, cubemap=False)
Get a single imageReturns 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 arrayArguments
Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
Name of the robot with the camera
Whether the camera is an External Camera
Whether to capture 3D images (default: False).
Whether to capture cubemap images otherwise equirectangular (default: False).
getImages
RobotClient.getImages(
camera_name, image_types: List[ImageType], robot_name="", capture_3d=False, cubemap=False
)
Get multiple images
Arguments
simGetImages
RobotClient.simGetImages(
requests: ImageRequest, robot_name="", external=False, capture_3d=False, cubemap=False
)
Get multiple images
Arguments
list[ImageRequest]: Images required
Name of robot associated with the camera
Whether the camera is an External Camera
Whether to capture 3D images (default: False).
Whether to capture cubemap images otherwise equirectangular (default: False).
Returns
list[ImageResponse]
simGetImagesAlongTrajectory
RobotClient.simGetImagesAlongTrajectory(
poses: List[Pose], requests, robot_name="", external=False, capture_3d=False, cubemap=False
)
Get images along a trajectory (specified by position and pose) when
Arguments
A list of poses of the robot, at which images are to be requested
list[ImageRequest]: Images required
Name of robot associated with the camera
Whether the camera is an External Camera, defaults to False
Whether to capture 3d images (default: False).
Whether to capture cubemap images otherwise equirectangular (default: False).
simGetPresetLensSettings
RobotClient.simGetPresetLensSettings(
camera_name: str, robot_name: str = "", external: bool = False
)
simGetLensSettings
RobotClient.simGetLensSettings(
camera_name: str, robot_name: str = "", external=False
)
simSetPresetLensSettings
RobotClient.simSetPresetLensSettings(
preset_lens_settings,
camera_name: str,
robot_name: str = "",
external=False,
)
No description provided!
simGetPresetFilmbackSettings
RobotClient.simGetPresetFilmbackSettings(
camera_name, robot_name="", external=False
)
No description provided!
simSetPresetFilmbackSettings
RobotClient.simSetPresetFilmbackSettings(
preset_filmback_settings, camera_name, robot_name="", external=False
)
No description provided!
simGetFilmbackSettings
RobotClient.simGetFilmbackSettings(camera_name, robot_name="", external=False)
No description provided!
simSetFilmbackSettings
RobotClient.simSetFilmbackSettings(
sensor_width, sensor_height, camera_name, robot_name="", external=False
)
No description provided!
simGetFocalLength
RobotClient.simGetFocalLength(camera_name, robot_name="", external=False)
No description provided!
simSetFocalLength
RobotClient.simSetFocalLength(
focal_length, camera_name, robot_name="", external=False
)
No description provided!
simEnableManualFocus
RobotClient.simEnableManualFocus(
enable, camera_name, robot_name="", external=False
)
No description provided!
simGetFocusDistance
RobotClient.simGetFocusDistance(camera_name, robot_name="", external=False)
No description provided!
simSetFocusDistance
RobotClient.simSetFocusDistance(
focus_distance, camera_name, robot_name="", external=False
)
No description provided!
simGetFocusAperture
RobotClient.simGetFocusAperture(camera_name, robot_name="", external=False)
No description provided!
simSetFocusAperture
RobotClient.simSetFocusAperture(
focus_aperture, camera_name, robot_name="", external=False
)
No description provided!
simEnableFocusPlane
RobotClient.simEnableFocusPlane(enable, camera_name, robot_name="", external=False)
No description provided!
simGetCurrentFieldOfView
RobotClient.simGetCurrentFieldOfView(camera_name, robot_name="", external=False)
No description provided!
simTestLineOfSightToPoint
RobotClient.simTestLineOfSightToPoint(point, robot_name="")
simTestLineOfSightBetweenPoints
RobotClient.simTestLineOfSightBetweenPoints(point1, point2)
simGetWorldExtents
RobotClient.simGetWorldExtents()
simRunConsoleCommand
RobotClient.simRunConsoleCommand(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 airgen needed!
simGetMeshPositionVertexBuffers
RobotClient.simGetMeshPositionVertexBuffers()
simGetCollisionInfo
RobotClient.simGetCollisionInfo(robot_name="")
simSetRobotPose
RobotClient.simSetRobotPose(pose:Pose, ignore_collision=True, sweep=False, robot_name="", bounds_trim=Vector3r(0.05, 0.05, 0.05), world_space=False, on_ground=False, ground_trace_range_up=GROUND_TRACE_RANGE_DEFAULT, ground_trace_range_down=GROUND_TRACE_RANGE_DEFAULT, timeout_sec=10)
Set the pose of the robotNote:
When world_space is False (default), the pose is specified relative to the robot’s local coordinate frame,
established at its initial position.
Arguments
Desired Pose of the robot.
Whether to ignore collision at the target pose.
Whether to sweep for collisions from the current pose to the target pose.
Name of the robot.
Amount to shrink the robot’s collision bounds when ignore_collision is False. Useful for fine-tuning collision detection and avoiding false positives at the edges.
Whether the input pose is in world coordinate frame.
Whether to set the robot’s altitude to ground level while setting its position.
From what distance above the Robot’s current altitude do we start looking for the ground (default is 13 KM).
How much distance below the Robot’s current altitude do we stop looking for the ground (default is 13 KM).
Timeout to find ground location (if on_ground is True).
simSetRobotGeoPose
RobotClient.simSetRobotGeoPose(geopose:GeoPose, ignore_collision:bool, sweep=False, robot_name="", bounds_trim=Vector3r(0.05, 0.05, 0.05), on_ground=False, ground_trace_range_up=GROUND_TRACE_RANGE_DEFAULT, ground_trace_range_down=GROUND_TRACE_RANGE_DEFAULT, timeout_sec=10)
Set the Geodetic pose of the robot
Arguments
Desired Geodetic Pose of the robot
Whether to ignore collision at the target pose
Whether to sweep for collisions from the current pose to the target pose
Name of the robot
Amount to shrink the robot’s collision bounds when ignore_collision is False. Useful for fine-tuning collision detection and avoiding false positives at the edges.
Whether to set the robot’s altitude to ground level while setting its position
From what distance above the Robot’s current altitude do we start looking for the ground (default is 13 KM)
How much distance below the Robot’s current altitude do we stop looking for the ground (default is 13 KM)
Timeout to find ground location (if on_ground is True)
simSetGeoReference
RobotClient.simSetGeoReference(geopoint:GeoPoint)
simGetGeoReference
RobotClient.simGetGeoReference()
simGetRobotPose
RobotClient.simGetRobotPose(world_space=False, robot_name="")
Returns the Pose of the robotNote:
When world_space is False (default), the returned pose is relative to the robot’s local coordinate frame,
established at its initial position.
Arguments
simSetTraceLine
RobotClient.simSetTraceLine(color_rgba, thickness=1.0, robot_name="")
Modify the color and thickness of the line when Tracing is enabledTracing can be enabled by pressing T in the Editor or setting
EnableTrace to True in the Settings for the robotsimGetObjectPose
RobotClient.simGetObjectPose(object_name)
simSetObjectPose
RobotClient.simSetObjectPose(object_name, pose, teleport=True)
Set the pose of the object(actor) in the environmentThe 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
Arguments
simSetObjectGeoPose
RobotClient.simSetObjectGeoPose(object_name, geopose, teleport=True)
Set the pose of the object(actor) in the environmentThe 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
Arguments
simGetObjectScale
RobotClient.simGetObjectScale(object_name)
simSetObjectScale
RobotClient.simSetObjectScale(object_name, scale_vector)
simGetObjectDimensions
RobotClient.simGetObjectDimensions(object_name)
simGetObjectCenter
RobotClient.simGetObjectCenter(object_name)
simListSceneObjects
RobotClient.simListSceneObjects(name_regex=".*")
Lists the objects present in the simulation environmentNote:
Default behaviour is to list all objects, regex can be used to return smaller list of matching objects.
Will return an empty list, if name_regex is empty.
simListSceneObjectsByTag
RobotClient.simListSceneObjectsByTag(tag_regex=".*")
Lists the objects present in the environment matching the input tag regexNote:
Default behaviour is to list all objects with atleast one tag, regex can be used to return a specific list of objects with matching tags.
Will return an empty list, if tag_regex is empty.
simLoadLevel
RobotClient.simLoadLevel(level_name)
simListAssets
RobotClient.simListAssets(filter=".*")
Retrieves a list of asset names from the Asset Registry, optionally filtered by a regex pattern.Note:
Default behaviour is to list all assets, regex can be used to return smaller list of matching assets.
Will return an empty list, if filter is empty.
simSpawnObject
RobotClient.simSpawnObject(
object_name,
asset_name,
object_tags=[],
pose:Pose = Pose.ZERO,
scale:Vector3r = Vector3r.ONE,
physics_enabled:bool = False,
)
Spawns an object in the world using an existing asset
Arguments
Desired name of new object
Name of asset(mesh) in the project database
List of tags to assign the object
Desired pose of object in world space
Desired scale of object
Whether to enable physics for the object (default is False)
simSpawnObjectFromPath
Spawns an object in the sim using a glTF/glb file path
Arguments
Desired name of new object
Path to the desired glTF or glb asset
List of tags to assign the object
Desired pose of object in world space
Desired scale of object
Whether the object should be unlit (default is False)
Whether to enable physics for the object (default is False)
Whether to use the mesh polygons for collision detection (default is False)
Whether the object should have navigation enabled (default is False)
simSpawnObjectFromURL
Spawns an object in the sim using a glb asset url
Arguments
Desired name of new object
URL address of the desired glb asset
List of tags to assign the object
Desired pose of object in world space
Desired scale of object
Whether the object should be unlit (default is False)
Whether to enable physics for the object (default is False)
Whether to use the mesh polygons for collision detection (default is False)
Whether the object should have navigation enabled (default is False)
simSpawnLight
RobotClient.simSpawnLight(
name,
properties:LightProperties,
mobility=RenderingMobility.Dynamic_Stationary,
tags=[],
pose:Pose = Pose.ZERO,
)
Spawns a light in the world with the specified properties
Arguments
Desired name of the new light object
Light properties to set (see LightProperties)
Rendering mobility type (default is Dynamic_Stationary, see RenderingMobility)
List of tags to assign the object
Desired pose of light in world space
simSetLightProperties
RobotClient.simSetLightProperties(light_name, properties:LightProperties)
simSetLightEnabled
RobotClient.simSetLightEnabled(light_name, value:bool)
simSetLightIntensity
RobotClient.simSetLightIntensity(light_name, value, unit:LightIntensityUnit = LightIntensityUnit.NoChange, indirect_scaling=-1.0)
Change ONLY the intensity value of the named light
Arguments
simDestroyObject
RobotClient.simDestroyObject(object_name)
simSetSegmentationObjectID
RobotClient.simSetSegmentationObjectID(mesh_name, object_id, is_name_regex=False)
Set segmentation ID for specific objects
Arguments
simSetSegmentationInstanceID
RobotClient.simSetSegmentationInstanceID(mesh_name, instance_id, is_name_regex=False)
Set segmentation ID for specific instances
Arguments
simGetSegmentationObjectID
RobotClient.simGetSegmentationObjectID(mesh_name)
simAddDetectionFilterMeshName
RobotClient.simAddDetectionFilterMeshName(
camera_name, image_type, mesh_name, robot_name="", external=False
)
Add mesh name to detect in wild card formatFor example: simAddDetectionFilterMeshName(“Car_”) will detect all instance named “Car_”
Arguments
Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
mesh name in wild card format
Robot which the camera is associated with
Whether the camera is an External Camera
simSetDetectionFilterRadius
RobotClient.simSetDetectionFilterRadius(
camera_name, image_type, radius_cm, robot_name="", external=False
)
Set detection radius for all cameras
Arguments
Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
Radius in [cm]
Robot which the camera is associated with
Whether the camera is an External Camera
simClearDetectionMeshNames
RobotClient.simClearDetectionMeshNames(
camera_name, image_type, robot_name="", external=False
)
Clear all mesh names from detection filter
simGetDetections
RobotClient.simGetDetections(
camera_name, image_type, robot_name="", external=False
)
Get current detections
Arguments
simPrintLogMessage
RobotClient.simPrintLogMessage(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.simGetCameraInfo
RobotClient.simGetCameraInfo(camera_name, robot_name="", external=False)
Get details about the camera
Arguments
simGetDistortionParams
RobotClient.simGetDistortionParams(camera_name, robot_name="", external=False)
Get camera distortion parameters
Arguments
simSetDistortionParams
RobotClient.simSetDistortionParams(
camera_name, distortion_params, robot_name="", external=False
)
Set camera distortion parameters
Arguments
Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
Dictionary of distortion param names and corresponding values
Robot which the camera is associated with
Whether the camera is an External Camera
simSetDistortionParam
RobotClient.simSetDistortionParam(
camera_name, param_name, value, robot_name="", external=False
)
Set single camera distortion parameter
Arguments
Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
Name of distortion parameter
Value of distortion parameter
Robot which the camera is associated with
Whether the camera is an External Camera
simSetCameraPose
RobotClient.simSetCameraPose(camera_name, pose, robot_name="", external=False)
- Control the pose of a selected camera
simSetCameraFov
RobotClient.simSetCameraFov(
camera_name, fov_degrees, robot_name="", external=False
)
simCameraLookAt
RobotClient.simCameraLookAt(camera_name, pose, robot_name="")
- Control the pose of a selected camera
simGetGroundTruthKinematics
RobotClient.simGetGroundTruthKinematics(robot_name="")
simSetKinematics
RobotClient.simSetKinematics(state, ignore_collision, robot_name="")
Set the kinematics state of the robotIf you don’t want to change position (or orientation) then just set components of position (or orientation) to floating point nan values
simGetGroundTruthEnvironment
RobotClient.simGetGroundTruthEnvironment(robot_name="")
getImuData
RobotClient.getImuData(imu_name="", robot_name="")
getBarometerData
RobotClient.getBarometerData(barometer_name="", robot_name="")
getMagnetometerData
RobotClient.getMagnetometerData(
magnetometer_name="", robot_name=""
)
getGpsData
RobotClient.getGpsData(gps_name="", robot_name="")
getDistanceSensorData
RobotClient.getDistanceSensorData(
distance_sensor_name="", robot_name=""
)
getLidarData
RobotClient.getLidarData(lidar_name="", robot_name="")
simGetLidarSegmentation
RobotClient.simGetLidarSegmentation(lidar_name="", robot_name="")
NOTE: Deprecated API, use
getLidarData() API instead
Returns Segmentation ID of each point’s collided object in the last Lidar updateArguments
simFlushPersistentMarkers
RobotClient.simFlushPersistentMarkers()
Clear any persistent markers - those plotted with setting
is_persistent=True in the APIs belowsimPlotPoints
RobotClient.simPlotPoints(
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
Arguments
simPlotLineStrip
RobotClient.simPlotLineStrip(
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]
Arguments
List of 3D locations of line start and end points, specified as Vector3r objects
desired RGBA values from 0.0 to 1.0
Thickness of line
Duration (seconds) to plot for
If set to True, the desired object will be plotted for infinite time.
simPlotLineList
RobotClient.simPlotLineList(
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]
Arguments
List of 3D locations of line start and end points, specified as Vector3r objects. Must be even
desired RGBA values from 0.0 to 1.0
Thickness of line
Duration (seconds) to plot for
If set to True, the desired object will be plotted for infinite time.
simPlotArrows
RobotClient.simPlotArrows(
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]
Arguments
List of 3D start positions of arrow start positions, specified as Vector3r objects
List of 3D end positions of arrow start positions, specified as Vector3r objects
desired RGBA values from 0.0 to 1.0
Thickness of line
Size of arrow head
Duration (seconds) to plot for
If set to True, the desired object will be plotted for infinite time.
simPlotStrings
RobotClient.simPlotStrings(
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.
Arguments
List of strings to plot
List of positions where the strings should be plotted. Should be in one-to-one correspondence with the strings’ list
Font scale of transform name
desired RGBA values from 0.0 to 1.0
Duration (seconds) to plot for
simPlotTransforms
RobotClient.simPlotTransforms(
poses, scale=5.0, thickness=5.0, duration=-1.0, is_persistent=False
)
Plots a list of transforms in World NED frame.
Arguments
List of Pose objects representing the transforms to plot
Length of transforms’ axes
Thickness of transforms’ axes
Duration (seconds) to plot for
If set to True, the desired object will be plotted for infinite time.
simPlotTransformsWithNames
RobotClient.simPlotTransformsWithNames(
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.
Arguments
List of Pose objects representing the transforms to plot
List of strings with one-to-one correspondence to list of poses
Length of transforms’ axes
Thickness of transforms’ axes
Font scale of transform name
desired RGBA values from 0.0 to 1.0 for the transform name
Duration (seconds) to plot for
startRecording
RobotClient.startRecording()
Start RecordingRecording will be done according to the settings
stopRecording
RobotClient.stopRecording()
Stop Recording
isRecording
RobotClient.isRecording()
simSetWind
RobotClient.simSetWind(wind)
simCreateVoxelGrid
RobotClient.simCreateVoxelGrid(position, x, y, z, res, of)
simBuildSDF
RobotClient.simBuildSDF(position, x, y, z, res)
Construct a signed distance field of the environment centered at position,
and with dimensions (x, y, z). Internally, the SDF is stored as a special
case of a voxel grid with floating point distances instead of boolean occupancy.
simCheckOccupancy
RobotClient.simCheckOccupancy(position)
simGetSignedDistance
RobotClient.simGetSignedDistance(position)
Get signed distance of a point (distance to the closest ‘object surface’)
in the environment. Requires signed distance field to be built beforehand.Distance is positive if the point is in free space, and negative if the point is
inside an object.
simGetSignedDistances
RobotClient.simGetSignedDistances(positions)
Get signed distance of a list of points (distance to the closest ‘object surface’)
in the environment. Requires signed distance field to be built beforehand.Distance is positive if the point is in free space, and negative if the point is
inside an object.
simGetSDFGradient
RobotClient.simGetSDFGradient(position)
Get the SDF gradient at a point (vector pointing away from the closest
‘object surface’) in the environment. Requires signed distance field to be built
beforehand.
simCheckInVolume
RobotClient.simCheckInVolume(position, volume_object_name)
simProjectToFreeSpace
RobotClient.simProjectToFreeSpace(position, mindist)
Project a given point into free space using the SDF, with a specified minimum clearance
from existing objects. Returns the same point if the point is already free, else follows
the SDF gradient to find a free point that satisfies the minimum distance constraint.
Arguments
simSaveSDF
RobotClient.simSaveSDF(filepath)
simLoadSDF
RobotClient.simLoadSDF(filepath)
simGetRandomFreePoint
RobotClient.simGetRandomFreePoint(search_radius, robot_name="")
Return a random free (unoccupied) point (local space) within a radius around the robot.
Arguments
simPlanPathToRandomFreePoint
RobotClient.simPlanPathToRandomFreePoint(search_radius:float, smooth_path:bool = False, draw_path:bool = False, robot_name:str ="")
Plan a collision-free path to a random point within a radius around the robot and return the intermediate waypoints (local space).
Arguments
simPlanPathToRandomizeGoal
RobotClient.simPlanPathToRandomizeGoal(
start: Vector3r,
goal: Vector3r,
search_radius: float,
num_trials: int,
smooth_path: bool = False,
draw_path: bool = False,
start_is_local: bool = True,
goal_is_local: bool = True,
robot_name: str = ""
)
Plans a collision-free path from the specified start position to a randomly selected free point within a given radius around the goal position.
The function attempts up to
num_trials random samples to find a valid, collision-free goal, and returns the intermediate waypoints (local space) of the planned path.Arguments
Start position.
Center position around which to randomize the goal.
Radius (in meters) around the goal to search for a free point.
Number of random samples to attempt for finding a free goal point.
If True, returns a smooth spline path; otherwise, returns a list of coarse waypoints. Defaults to False.
If True, visualizes the path in the environment. Defaults to False.
Name of the robot. Defaults to "".
If True, the start position is in the robot’s local frame; otherwise, in the world/global frame. Defaults to True.
If True, the goal position is in the robot’s local frame; otherwise, in the world/global frame. Defaults to True.
simPlanPath
RobotClient.simPlanPath(
start: Vector3r,
goal: Vector3r,
smooth_path: bool = False,
draw_path: bool = False,
start_is_local: bool = True,
goal_is_local: bool = True,
robot_name: str = ""
)
Plans a collision-free path between the specified start and goal points, returning the intermediate waypoints (local space).
Arguments
Start position
Goal position
If True, returns a smooth spline; otherwise, returns a list of coarse waypoints. Defaults to False.
If True, draws the path. Defaults to False.
Name of the robot. Defaults to "".
If True, start position is in the robot’s local frame; if False, in world/global frame. Defaults to True.
If True, goal position is in the robot’s local frame; if False, in world/global frame. Defaults to True.
simPlanPathGeo
RobotClient.simPlanPathGeo(
start: GeoPoint,
goal: GeoPoint,
smooth_path: bool = False,
draw_path: bool = False,
robot_name: str = ""
)
Plans a collision-free path between the specified start and goal geodetic locations (LLA), returning the intermediate waypoints (local NED).
Arguments
Start Geodetic Location (LLA)
Goal Geodetic Location (LLA)
If True, returns a smooth spline; otherwise, returns a list of coarse waypoints. Defaults to False.
If True, draws the path. Defaults to False.
Name of the robot. Defaults to "".
getNavMeshInfo
isPointInCollision
RobotClient.isPointInCollision(point)
isAnyPointInCollisionBatch
RobotClient.isAnyPointInCollisionBatch(points)
simAddRobot
RobotClient.simAddRobot(robot_name, robot_type, robot_model, pose, radius_override=-1, height_override=-1)
Add a robot to the simulation with the specified name, type, model, and initial pose.
Arguments
Unique name for the robot (e.g., “Drone5”).
Type of robot to add (e.g., “simpleflight”, “cvmover”).
Model name of the robot (e.g., “astro”, “ghostv60”).
The initial pose (position and orientation) of the robot in world coordinates.
If > 0, overrides the robot’s default collision radius (meters). Defaults to -1 (no override).
If > 0, overrides the robot’s default collision height (meters). Defaults to -1 (no override).
listRobots
RobotClient.listRobots()
getSettingsString
RobotClient.getSettingsString()
simCreateWaypoint
RobotClient.simCreateWaypoint(context = "", robot_name = "")
Creates a waypoint using the robot transform.
The created waypoint will be associated with the specified waypoints-context.If context isn’t specified, it’ll default to the last-used context.
If there’s no context present and context isn’t specified, a context named ‘defaultWaypoints’ will be auto created.
simCreateWaypointFromPose
RobotClient.simCreateWaypointFromPose(pose, context = "")
Creates a waypoint using the robot transform.
The created waypoint will be associated with the specified waypoints-context.If context isn’t specified, it’ll default to the last-used context.
If there’s no context present and context isn’t specified, a context named ‘defaultWaypoints’ will be auto created.
simDeleteWaypoints
RobotClient.simDeleteWaypoints(context = "", only_recent = True, keep_context_alive = True)
Deletes waypoints for a specified contextIf ‘only_recent’ is True, it’ll delete the youngest waypoint of the specified waypoints-context.
If ‘only_recent’ is False, it’ll delete all waypoints for the specified context.If context isn’t specified, it’ll default to the last-used context.
If context isn’t specified and there’s no last-used context, it’ll throw an error.
simDeleteAllWaypoints
RobotClient.simDeleteAllWaypoints()
Deletes all waypoints and all waypoint-contexts
simGetWaypointDataAsCsv
RobotClient.simGetWaypointDataAsCsv(context = "")
Get the waypoints data of a waypoints-context as a CSV formatted string.
If context isn’t specified, it’ll default to the last-used context.
If context isn’t specified and there’s no last-used context, it’ll throw an error.
simGetWaypointDataAsJson
RobotClient.simGetWaypointDataAsJson(context = "")
Get the waypoints data of a waypoints-context as a JSON string.
If context isn’t specified, it’ll default to the last-used context.
If context isn’t specified and there’s no last-used context, it’ll throw an error.
simSetWaypointColor
RobotClient.simSetWaypointColor(color_rgb, index, context = "")
Changes the color of a given waypoint.
If context isn’t specified, it’ll default to the last-used context.
If context isn’t specified and there’s no last-used context, it’ll throw an error.
Arguments
simResetWaypointColor
RobotClient.simResetWaypointColor(index, context = "")
Resets the color of a given waypoint to the original.
If context isn’t specified, it’ll default to the last-used context.
If context isn’t specified and there’s no last-used context, it’ll throw an error.
Arguments
cancelLastTask
RobotClient.cancelLastTask(robot_name="")
simSetGroundTraceParams
RobotClient.simSetGroundTraceParams(enabled, range_up=GROUND_TRACE_RANGE_DEFAULT, range_down=GROUND_TRACE_RANGE_DEFAULT)
Sets the various Ground Trace parameters.
This affects the “reset” behavior, and the “simAddRobot” behavior.
Arguments
Enable or Disable Ground Trace.
From what distance above the robot’s current altitude do we start looking for the ground (default is 13 KM)
How much distance below the robot’s current altitude do we stop looking for the ground (default is 13 KM)
simGetAllPhysicsControlNames
RobotClient.simGetAllPhysicsControlNames(robot_name="")
simSetPhysicsControlTargetPose
RobotClient.simSetPhysicsControlTargetPose(name, pose, velocity_delta_time=0.0, robot_name="")
Sets the target pose for a specific physics control of a robot.
Arguments
simSetPhysicsControlTargetPoses
RobotClient.simSetPhysicsControlTargetPoses(names, poses, velocity_delta_time=0.0, robot_name="")
Sets the target poses for multiple physics controls of a robot.
The length of ‘poses’ and ‘names’ must be the same.
Arguments
List of Physics Control names.
List of Target Poses.
If this is non-zero, the target velocity will be calculated using the current target position. But if this is zero, the target velocity will be set to zero.
Name of the robot.
simSetPhysicsControlMultiplier
RobotClient.simSetPhysicsControlMultiplier(
name,
linear_strength=Vector3r.one(),
linear_damping_ratio=Vector3r.one(),
linear_extra_damping=Vector3r.one(),
max_force=Vector3r.one(),
angular_strength=1.0,
angular_damping_ratio=1.0,
angular_extra_damping=1.0,
max_torque=1.0,
robot_name=""
)
Multiplies a physics control’s properties with the input scaling factors
Arguments
Name of the physics control
Scaling factor for linear strength (default: Vector3r(1, 1, 1)).
Scaling factor for linear damping ratio (default: Vector3r(1, 1, 1)).
Scaling factor for linear extra damping (default: Vector3r(1, 1, 1)).
Scaling factor for maximum force (default: Vector3r(1, 1, 1)).
Scaling factor for angular strength (default: 1.0).
Scaling factor for angular damping ratio (default: 1.0).
Scaling factor for angular extra damping (default: 1.0).
Scaling factor for maximum torque (default: 1.0).
Name of the robot
simSetHero
RobotClient.simSetHero(robot_name="")