The Client connects CARLA to the server which runs the simulation. Both server and client contain a CARLA library (libcarla) with some differences that allow communication between them. Many clients can be created and each of these will connect to the RPC server inside the simulation to send commands. The simulation runs server-side. Once the connection is established, the client will only receive data retrieved from the simulation. Walkers are the exception. The client is in charge of managing pedestrians so, if you are running a simulation with multiple clients, some issues may arise. For example, if you spawn walkers through different clients, collisions may happen, as each client is only aware of the ones it is in charge of.
The client also has a recording feature that saves all the information of a simulation while running it. This allows the server to replay it at will to obtain information and experiment with it. [Here](adv_recorder.md) is some information about how to use this recorder.
Executes a list of commands on a single simulation step and retrieves no information. If you need information about the response of each command, use the **<font color="#7fb800">apply_batch_sync()</font>** function right below this one.
[Here](https://github.com/carla-simulator/carla/blob/10c5f6a482a21abfd00220c68c7f12b4110b7f63/PythonAPI/examples/spawn_npc.py#L126) is an example on how to delete the actors that appear in carla.ActorList all at once.
Executes a list of commands on a single simulation step, blocks until the commands are linked, and returns a list of <b>command.Response</b> that can be used to determine whether a single command succeeded or not. [Here](https://github.com/carla-simulator/carla/blob/10c5f6a482a21abfd00220c68c7f12b4110b7f63/PythonAPI/examples/spawn_npc.py#L112-L116) is an example of it being used to spawn actors.
Returns a list of strings containing the paths of the maps available on server. These paths are dynamic, they will be created during the simulation and so you will not find them when looking up in your files. One of the possible returns for this method would be:
Returns the client libcarla version by consulting it in the "Version.h" file. Both client and server can use different libcarla versions but some issues may arise regarding unexpected incompatibilities.
Time in seconds where to start playing the simulation. Negative is read as beginning from the end, being -10 just 10 seconds before the recording finished.
The server will start running the simulation `name` previously recorded. The time to start and stop can be stated and if the recreation finishes, the vehicles will continue their behaviour as usual, managed by the server. During the simulation we can follow a specific actor using its ID.
# --------------------------------------
- def_name:generate_opendrive_world
params:
- param_name:opendrive
type:str
doc:>
OpenDRIVE data as `string`.
doc:>
Loads a new world with a basic physical topology generated from an OpenDRIVE file passed as `string`.
It is similar to `client.load_world(map_name)` but allows for custom OpenDRIVE maps in server side.
Cars can drive around the map, but there are no graphics besides the road and sidewalks.
The terminal will show the information registered for actors considered blocked. An actor is considered blocked when it does not move a minimum distance in a period of time, being these `min_distance` and `min_time`.
When true, will show all the details per frame (traffic light states, positions of all actors, orientation and animation data...), but by default it will only show a summary.
The information saved by the recorder will be parsed and shown in your terminal as text (frames, times, events, state, positions...). The information shown can be specified by using the `show_all` parameter. [Here](ref_recorder_binary_file_format.md) is some more information about how to read the recorder file.
Name of the file to write the recorded data. A simple name will save the recording in 'CarlaUE4/Saved/recording.log'. Otherwise, if some folder appears in the name, it will be considered an absolute path.
The traffic manager is a module build on top of the CARLA API that handles any group of vehicles in order to simulate specific behaviours. This module manages every [carla.Vehicle]() that has been set to autopilot mode. Its main goal is to improve the traffic around the city so that the simulation runs under realistic conditions. While doing so, another goal is to give the users the option to customize the simulated traffic like never before.
In order to learn more, visit the [documentation](../traffic_manager) regarding this module.
# - PROPERTIES -------------------------
instance_variables:
# - METHODS ----------------------------
methods:
- def_name:force_lane_change
params:
- param_name:actor
type:carla.Actor
doc:>
Vehicle being forced to change lanes.
- param_name:direction
type:bool
doc:>
Destiny lane. __True__ is the one on the left and __False__ is the right one.
doc:>
Forces a vehicle to change either to the lane on its left or right (if existing) as indicated in `direction`. This method provokes the lane change no matter what, disregarding possible collisions.
# --------------------------------------
- def_name:ignore_actors_percentage
params:
- param_name:actor
type:carla.Actor
doc:>
The actor that is going to ignore others.
- param_name:perc
type:float
doc:>
Between 0 and 100. Amount of times collisions will be ignored.
doc:>
During the collision detection stage, which runs every frame, this method sets a percentage of times that collisions will be ignored for said `actor` and so, not computed.
# --------------------------------------
- def_name:ignore_lights_percentage
params:
- param_name:actor
type:carla.Actor
doc:>
The actor that is going to ignore traffic lights.
- param_name:perc
type:float
doc:>
Between 0 and 100. Amount of times traffic lights will be ignored.
return:Anything?
doc:>
During the traffic light stage, which runs every frame, this method sets a percentage of times that collisions with the bounding boxes of traffic lights will be ignored for said `actor` and so, not computed.
# --------------------------------------
- def_name:register_vehicles
params:
- param_name:actor_list
type:list(carla.Actor)
doc:>
List of actors to be subscribed.
doc:>
Registers a series of actors to a traffic manager to make it aware of them.
# --------------------------------------
- def_name:reset_traffic_lights
doc:>
Returns every group of traffic lights in a map to its initial state. The first traffic light of the group will turn green, the rest will be frozen in red and the time cycle will reset.
# --------------------------------------
- def_name:set_auto_lane_change
params:
- param_name:actor
type:carla.Actor
doc:>
The vehicle whose settings are changed.
- param_name:enable
type:bool
doc:>
When __True__, lane changes will be enabled.
doc:>
Sets the capability of a vehicle to perform lane changes when the traffic manager decides so. Otherwise, there will be none.
# --------------------------------------
- def_name:set_distance_to_leading_vehicle
params:
- param_name:actor
type:carla.Actor
doc:>
Vehicle whose safe distance is being changed.
- param_name:distance
type:float
doc:>
Meters between both vehicles.
doc:>
Sets the minimum safety distance for a vehicle to keep with the rest when stopped. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects.
# --------------------------------------
- def_name:set_collision_detection
params:
- param_name:reference_actor
type:carla.Actor
doc:>
Vehicle that is going to ignore collisions.
- param_name:other_actor
type:carla.Actor
doc:>
The actor that `reference_actor` is going to ignore collisions with.
- param_name:detect_collision
type:bool
doc:>
Set it to __True__ to enable collisions.
doc:>
Turns on/off collisions between a specific vehicle and another actor. In order to ignore all other vehicles, traffic lights or walkers, use the specific __ignore__ methods described in this same section.
# --------------------------------------
- def_name:set_global_max_speed_difference
params:
- param_name:percentage
type:float
doc:>
Between 0 and 100, difference between speed regarding the current limit.
doc:>
Sets the difference the vehicle's intended speed and its current speed limit. Speed limits can be exceeded by setting the `perc` to a negative value.
The percentage is 0 per default for every vehicle, meaning that the default behaviour makes them drive at their limit speed. If `perc` is 30 and the speed limit is 100, the vehicles' intended speed will be 70. If `perc` is -30 and the speed limit is 100, the vehicles' intended speed will be 130.
# --------------------------------------
- def_name:set_global_distance_to_leading_vehicle
params:
- param_name:distance
type:float
doc:>
Meters between vehicles.
doc:>
Sets a new minimum distance between stopped vehicles to keep for safety reasons. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects.
# --------------------------------------
- def_name:set_vehicle_max_speed_difference
params:
- param_name:actor
type:carla.Actor
doc:>
Vehicle whose speed behaviour is being changed.
- param_name:percentage
type:float
doc:>
Between 0 and 100, difference between speed regarding the current limit.
doc:>
Sets the difference the vehicle's intended speed and its current speed limit. Speed limits can be exceeded by setting the `perc` to a negative value.
The percentage is 0 per default for every vehicle, meaning that the default behaviour makes them drive at their limit speed. If `perc` is 30 and the speed limit is 100, the vehicle's intended speed will be 70. If `perc` is -30 and the speed limit is 100, the vehicle's intended speed will be 130.
# --------------------------------------
- def_name:unregister_vehicles
params:
- param_name:actor_list
type:list(carla.Actor)
doc:>
List of actors to be unsubscribed.
doc:>
Deletes a series of actors from the traffic manager's lists to stop being responsible of them.