diff --git a/Docs/python_api.md b/Docs/python_api.md index 0a70732e5..041aeca09 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -1,6 +1,40 @@ #Python API reference This reference contains all the details the Python API. To consult a previous reference for a specific CARLA release, change the documentation version using the panel in the bottom right corner.
This will change the whole documentation to a previous state. Remember that the latest version is the `dev` branch and may show features not available in any packaged versions of CARLA.
+## carla.AckermannControllerSettings +Manages the settings of the Ackermann PID controller. + +### Instance Variables +- **speed_kp** (_float_) +Proportional term of the speed PID controller. +- **speed_ki** (_float_) +Integral term of the speed PID controller. +- **speed_kd** (_float_) +Derivative term of the speed PID controller. +- **accel_kp** (_float_) +Proportional term of the acceleration PID controller. +- **accel_ki** (_float_) +Integral term of the acceleration PID controller. +- **accel_kd** (_float_) +Derivative term of the acceleration PID controller. + +### Methods +- **\__init__**(**self**, **speed_kp**=0.15, **speed_ki**=0.0, **speed_kd**=0.25, **accel_kp**=0.01, **accel_ki**=0.0, **accel_kd**=0.01) + - **Parameters:** + - `speed_kp` (_float_) + - `speed_ki` (_float_) + - `speed_kd` (_float_) + - `accel_kp` (_float_) + - `accel_ki` (_float_) + - `accel_kd` (_float_) + +##### Dunder methods +- **\__eq__**(**self**, **other**=[carla.AckermannControllerSettings](#carla.AckermannControllerSettings)) +- **\__ne__**(**self**, **other**=[carla.AckermannControllerSettings](#carla.AckermannControllerSettings)) +- **\__str__**(**self**) + +--- + ## carla.Actor CARLA defines actors as anything that plays a role in the simulation or can be moved around. That includes: pedestrians, vehicles, sensors and traffic signs (considering traffic lights as part of these). Actors are spawned in the simulation by [carla.World](#carla.World) and they need for a [carla.ActorBlueprint](#carla.ActorBlueprint) to be created. These blueprints belong into a library provided by CARLA, find more about them [here](bp_library.md). @@ -9,14 +43,22 @@ CARLA defines actors as anything that plays a role in the simulation or can be m A dictionary containing the attributes of the blueprint this actor was based on. - **id** (_int_) Identifier for this actor. Unique during a given episode. +- **type_id** (_str_) +The identifier of the blueprint this actor was based on, e.g. `vehicle.ford.mustang`. - **is_alive** (_bool_) Returns whether this object was destroyed using this actor handle. +- **is_active** (_bool_) +Returns whether this actor is active (True) or not (False). +- **is_dormant** (_bool_) +Returns whether this actor is dormant (True) or not (False) - the opposite of is_active. - **parent** (_[carla.Actor](#carla.Actor)_) Actors may be attached to a parent actor that they will follow around. This is said actor. - **semantic_tags** (_list(int)_) A list of semantic tags provided by the blueprint listing components for this actor. E.g. a traffic light could be tagged with `Pole` and `TrafficLight`. These tags are used by the semantic segmentation sensor. Find more about this and other sensors [here](ref_sensors.md#semantic-segmentation-camera). -- **type_id** (_str_) -The identifier of the blueprint this actor was based on, e.g. `vehicle.ford.mustang`. +- **actor_state** (_[carla.ActorState](#carla.ActorState)_) +Returns the [carla.ActorState](#carla.ActorState), which can identify if the actor is Active, Dormant or Invalid. +- **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_) +Bounding box containing the geometry of the actor. Its location and rotation are relative to the actor it is attached to. ### Methods - **add_angular_impulse**(**self**, **angular_impulse**) @@ -35,12 +77,6 @@ Applies an impulse at the center of mass of the actor. This method should be use Applies a torque at the center of mass of the actor. This method should be used for torques that are applied over a certain period of time. Use __add_angular_impulse()__ to apply a torque that only lasts an instant. - **Parameters:** - `torque` (_[carla.Vector3D](#carla.Vector3D) - degrees_) - Torque vector in global coordinates. -- **close_door**(**self**, **door_idx**) -Close the door door_idx if the vehicle has it. Use [carla.VehicleDoor.All](#carla.VehicleDoor.All) to close all available doors. - - **Parameters:** - - `door_idx` (_[carla.VehicleDoor](#carla.VehicleDoor)_) - door index. - - **Note:** _Only [carla.Vehicle](#carla.Vehicle) actors can use this method. -_ - **destroy**(**self**) Tells the simulator to destroy this actor and returns True if it was successful. It has no effect if it was already destroyed. - **Return:** _bool_ @@ -48,19 +84,6 @@ Tells the simulator to destroy this actor and returns True if it was succ _ - **disable_constant_velocity**(**self**) Disables any constant velocity previously set for a [carla.Vehicle](#carla.Vehicle) actor. -- **enable_chrono_physics**(**self**, **max_substeps**, **max_substep_delta_time**, **vehicle_json**, **powertrain_json**, **tire_json**, **base_json_path**) -Enables Chrono physics on a spawned vehicle. - - **Parameters:** - - `max_substeps` (_int_) - Max number of Chrono substeps. - - `max_substep_delta_time` (_int_) - Max size of substep. - - `vehicle_json` (_str_) - Path to vehicle json file relative to `base_json_path`. - - `powertrain_json` (_str_) - Path to powertrain json file relative to `base_json_path`. - - `tire_json` (_str_) - Path to tire json file relative to `base_json_path`. - - `base_json_path` (_str_) - Path to `chrono/data/vehicle` folder. E.g., `/home/user/carla/Build/chrono-install/share/chrono/data/vehicle/` (the final `/` character is required). - - **Note:** _Ensure that you have started the CARLA server with the `ARGS="--chrono"` flag. You will not be able to use Chrono physics without this flag set. -_ - - **Warning:** _Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics. -_ - **enable_constant_velocity**(**self**, **velocity**) Sets a vehicle's velocity vector to a constant value over time. The resulting velocity will be approximately the `velocity` being set, as with __set_target_velocity()__. - **Parameters:** @@ -69,16 +92,6 @@ Sets a vehicle's velocity vector to a constant value over time. The resulting ve _ - **Warning:** _Enabling a constant velocity for a vehicle managed by the [Traffic Manager](https://[carla.readthedocs.io](#carla.readthedocs.io)/en/latest/adv_traffic_manager/) may cause conflicts. This method overrides any changes in velocity by the TM. _ -- **open_door**(**self**, **door_idx**) -Open the door door_idx if the vehicle has it. Use [carla.VehicleDoor.All](#carla.VehicleDoor.All) to open all available doors. - - **Parameters:** - - `door_idx` (_[carla.VehicleDoor](#carla.VehicleDoor)_) - door index. - - **Note:** _Only [carla.Vehicle](#carla.Vehicle) actors can use this method. -_ -- **show_debug_telemetry**(**self**, **enabled**=True) -Enables or disables the telemetry on this vehicle. This shows information about the vehicles current state and forces applied to it in the spectator window. Only information for one vehicle can be shown so if you enable a second one, the previous will be automatically disabled. - - **Parameters:** - - `enabled` (_bool_) ##### Getters - **get_acceleration**(**self**) @@ -295,12 +308,25 @@ Returns the velocity vector registered for an actor in that tick. --- +## carla.ActorState +Class that defines the state of an actor. + +### Instance Variables +- **Invalid** +An actor is Invalid if a problem has occurred. +- **Active** +An actor is Active when it visualized and can affect other actors. +- **Dormant** +An actor is Dormant when it is not visualized and will not affect other actors through physics. For example, actors are dormant if they are on an unloaded tile in a large map. + +--- + ## carla.AttachmentType Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snipet in [carla.World.spawn_actor](#carla.World.spawn_actor) shows some sensors being attached to a car when spawned. Note that the attachment type is declared as an enum within the class. ### Instance Variables - **Rigid** -With this fixed attatchment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation. +With this fixed attachment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation. - **SpringArm** An attachment that expands or retracts the position of the actor, depending on its parent. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so [check the UE docs](https://docs.unrealengine.com/en-US/Gameplay/HowTo/UsingCameras/SpringArmComponents/index.html) to learn more about them.
Warning: The SpringArm attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. child_location = Location(0,0,2)). - **SpringArmGhost** @@ -554,6 +580,9 @@ Returns the world object currently active in the simulation. This world will be - **set_replayer_ignore_hero**(**self**, **ignore_hero**) - **Parameters:** - `ignore_hero` (_bool_) - Enables or disables playback of the hero vehicle during a playback of a recorded simulation. +- **set_replayer_ignore_spectator**(**self**, **ignore_spectator**) + - **Parameters:** + - `ignore_spectator` (_bool_) - Determines whether the recorded spectator movements will be replicated by the replayer. - **set_replayer_time_factor**(**self**, **time_factor**=1.0) When used, the time speed of the reenacted simulation is modified at will. It can be used several times while a playback is in curse. - **Parameters:** @@ -613,7 +642,7 @@ Class that defines conversion patterns that can be applied to a [carla.Image](#c ### Instance Variables - **CityScapesPalette** -Converts the image to a segmentated map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera). +Converts the image to a segmented map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera). - **Depth** Converts the image to a linear depth map. Used by the [depth camera](ref_sensors.md#depth-camera). - **LogarithmicDepth** @@ -929,6 +958,7 @@ Image height in pixels. - **width** (_int_) Image width in pixels. - **raw_data** (_bytes_) +Flattened array of pixel data, use reshape to create an image array. ### Methods - **convert**(**self**, **color_converter**) @@ -956,7 +986,7 @@ Class that embodies the intersections on the road described in the OpenDRIVE fil ### Instance Variables - **id** (_int_) -Identificator found in the OpenDRIVE file. +Identifier found in the OpenDRIVE file. - **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_) Bounding box encapsulating the junction lanes. @@ -1009,9 +1039,9 @@ Height where the landmark is placed. - **country** (_str_) Country code where the landmark is defined (default to OpenDRIVE is Germany 2017). - **type** (_str_) -Type identificator of the landmark according to the country code. +Type identifier of the landmark according to the country code. - **sub_type** (_str_) -Subtype identificator of the landmark according to the country code. +Subtype identifier of the landmark according to the country code. - **value** (_float_) Value printed in the signal (e.g. speed limit, maximum weight, etc). - **unit** (_str_) @@ -1245,7 +1275,7 @@ Every type except for NONE. --- ## carla.LidarDetection -Data contained inside a [carla.LidarMeasurement](#carla.LidarMeasurement). Each of these represents one of the points in the cloud with its location and its asociated intensity. +Data contained inside a [carla.LidarMeasurement](#carla.LidarMeasurement). Each of these represents one of the points in the cloud with its location and its associated intensity. ### Instance Variables - **point** (_[carla.Location](#carla.Location) - meters_) @@ -1270,7 +1300,7 @@ Number of lasers shot. - **horizontal_angle** (_float - radians_) Horizontal angle the LIDAR is rotated at the time of the measurement. - **raw_data** (_bytes_) -Received list of 4D points. Each point consists of [x,y,z] coordiantes plus the intensity computed for that point. +Received list of 4D points. Each point consists of [x,y,z] coordinates plus the intensity computed for that point. ### Methods - **save_to_disk**(**self**, **path**) @@ -1550,6 +1580,10 @@ Constructor for this class. Though a map is automatically generated when initial - `name` (_str_) - Name of the current map. - `xodr_content` (_str_) - .xodr content in string format. - **Return:** _list([carla.Transform](#carla.Transform))_ +- **cook_in_memory_map**(**self**, **path**) +Generates a binary file from the CARLA map containing information used by the Traffic Manager. This method is only used during the import process for maps. + - **Parameters:** + - `path` (_str_) - Path to the intended location of the stored binary map file. - **generate_waypoints**(**self**, **distance**) Returns a list of waypoints with a certain distance between them for every lane and centered inside of it. Waypoints are not listed in any particular order. Remember that waypoints closer than 2cm within the same road, section and lane will have the same identificator. - **Parameters:** @@ -1704,6 +1738,7 @@ Image height in pixels. - **width** (_int_) Image width in pixels. - **raw_data** (_bytes_) +Flattened array of pixel data, use reshape to create an image array. ### Methods @@ -2492,6 +2527,8 @@ Adjust probability that in each timestep the actor will perform a right lane cha - **Parameters:** - `actor` (_[carla.Actor](#carla.Actor)_) - The actor that you wish to query. - `percentage` (_float_) - The probability of lane change in percentage units (between 0 and 100). +- **shut_down**(**self**) +Shuts down the traffic manager. - **update_vehicle_lights**(**self**, **actor**, **do_update**) Sets if the Traffic Manager is responsible of updating the vehicle lights, or not. Default is __False__. The traffic manager will not change the vehicle light status of a vehicle, unless its auto_update_status is st to __True__. @@ -2614,6 +2651,10 @@ Describes a rotation for an object according to Unreal Engine's axis system. Translates a 3D point from local to global coordinates using the current transformation as frame of reference. - **Parameters:** - `in_point` (_[carla.Location](#carla.Location)_) - Location in the space to which the transformation will be applied. +- **transform_vector**(**self**, **in_vector**) +Rotates a vector using the current transformation as frame of reference, without applying translation. Use this to transform, for example, a velocity. + - **Parameters:** + - `in_vector` (_[carla.Vector3D](#carla.Vector3D)_) - Vector to which the transformation will be applied. ##### Getters - **get_forward_vector**(**self**) @@ -2626,7 +2667,7 @@ Computes the 4-matrix representation of the inverse transformation. Computes the 4-matrix representation of the transformation. - **Return:** _list(list(float))_ - **get_right_vector**(**self**) -Computes a right vector using the rotatio of the object. +Computes a right vector using the rotation of the object. - **Return:** _[carla.Vector3D](#carla.Vector3D)_ - **get_up_vector**(**self**) Computes an up vector using the rotation of the object. @@ -2748,6 +2789,13 @@ Returns a vector with the same direction and unitary length. Computes the squared length of the vector. - **Return:** _float_ +##### Getters +- **get_vector_angle**(**self**, **vector**) +Computes the angle between a pair of 3D vectors in radians. + - **Parameters:** + - `vector` (_[carla.Vector3D](#carla.Vector3D)_) + - **Return:** _float_ + ##### Dunder methods - **\__abs__**(**self**) Returns a Vector3D with the absolute value of the components x, y and z. @@ -2770,13 +2818,22 @@ Returns the axis values for the vector parsed as string. ## carla.Vehicle Inherited from _[carla.Actor](#carla.Actor)_
-One of the most important group of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in [carla.BlueprintLibrary](#carla.BlueprintLibrary) to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the traffic manager. +One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in [carla.BlueprintLibrary](#carla.BlueprintLibrary) to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the traffic manager. ### Instance Variables - **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_) Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to. ### Methods +- **apply_ackermann_control**(**self**, **control**) +Applies an Ackermann control object on the next tick. + - **Parameters:** + - `control` (_[carla.VehicleAckermannControl](#carla.VehicleAckermannControl)_) +- **apply_ackermann_controller_settings**(**self**, **settings**) +Applies a new Ackermann control settings to this vehicle in the next tick. + - **Parameters:** + - `settings` (_[carla.AckermannControllerSettings](#carla.AckermannControllerSettings)_) + - **Warning:** _This method does call the simulator._ - **apply_control**(**self**, **control**) Applies a control object on the next tick, containing driving parameters such as throttle, steering or gear shifting. - **Parameters:** @@ -2785,19 +2842,48 @@ Applies a control object on the next tick, containing driving parameters such as Applies a physics control object in the next tick containing the parameters that define the vehicle as a corporeal body. E.g.: moment of inertia, mass, drag coefficient and many more. - **Parameters:** - `physics_control` (_[carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl)_) +- **close_door**(**self**, **door_idx**) +Close the door `door_idx` if the vehicle has it. Use [carla.VehicleDoor.All](#carla.VehicleDoor.All) to close all available doors. + - **Parameters:** + - `door_idx` (_[carla.VehicleDoor](#carla.VehicleDoor)_) - door index. - **enable_carsim**(**self**, **simfile_path**) Enables the CarSim physics solver for this particular vehicle. In order for this function to work, there needs to be a valid license manager running on the server side. The control inputs are redirected to CarSim which will provide the position and orientation of the vehicle for every frame. - **Parameters:** - `simfile_path` (_str_) - Path to the `.simfile` file with the parameters of the simulation. +- **enable_chrono_physics**(**self**, **max_substeps**, **max_substep_delta_time**, **vehicle_json**, **powertrain_json**, **tire_json**, **base_json_path**) +Enables Chrono physics on a spawned vehicle. + - **Parameters:** + - `max_substeps` (_int_) - Max number of Chrono substeps. + - `max_substep_delta_time` (_int_) - Max size of substep. + - `vehicle_json` (_str_) - Path to vehicle json file relative to `base_json_path`. + - `powertrain_json` (_str_) - Path to powertrain json file relative to `base_json_path`. + - `tire_json` (_str_) - Path to tire json file relative to `base_json_path`. + - `base_json_path` (_str_) - Path to `chrono/data/vehicle` folder. E.g., `/home/user/carla/Build/chrono-install/share/chrono/data/vehicle/` (the final `/` character is required). + - **Note:** _Ensure that you have started the CARLA server with the `ARGS="--chrono"` flag. You will not be able to use Chrono physics without this flag set. +_ + - **Warning:** _Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics. +_ - **is_at_traffic_light**(**self**) Vehicles will be affected by a traffic light when the light is red and the vehicle is inside its bounding box. The client returns whether a traffic light is affecting this vehicle according to last tick (it does not call the simulator). - **Return:** _bool_ +- **open_door**(**self**, **door_idx**) +Open the door `door_idx` if the vehicle has it. Use [carla.VehicleDoor.All](#carla.VehicleDoor.All) to open all available doors. + - **Parameters:** + - `door_idx` (_[carla.VehicleDoor](#carla.VehicleDoor)_) - door index. +- **show_debug_telemetry**(**self**, **enabled**=True) +Enables or disables the telemetry on this vehicle. This shows information about the vehicles current state and forces applied to it in the spectator window. Only information for one vehicle can be shown so that, if you enable a second one, the previous will be automatically disabled. + - **Parameters:** + - `enabled` (_bool_) - **use_carsim_road**(**self**, **enabled**) Enables or disables the usage of CarSim vs terrain file specified in the `.simfile`. By default this option is disabled and CarSim uses unreal engine methods to process the geometry of the scene. - **Parameters:** - `enabled` (_bool_) ##### Getters +- **get_ackermann_controller_settings**(**self**) +Returns the last Ackermann control settings applied to this vehicle. + - **Return:** _[carla.AckermannControllerSettings](#carla.AckermannControllerSettings)_ + - **Warning:** _This method does call the simulator to retrieve the value._ - **get_control**(**self**) The client returns the control applied in the last tick. The method does not call the simulator. - **Return:** _[carla.VehicleControl](#carla.VehicleControl)_ @@ -2853,6 +2939,37 @@ _ --- +## carla.VehicleAckermannControl +Manages the basic movement of a vehicle using Ackermann driving controls. + +### Instance Variables +- **steer** (_float_) +Desired steer (rad). Positive value is to the right. Default is 0.0. +- **steer_speed** (_float_) +Steering velocity (rad/s). Zero steering angle velocity means change the steering angle as quickly as possible. Default is 0.0. +- **speed** (_float_) +Desired speed (m/s). Default is 0.0. +- **acceleration** (_float_) +Desired acceleration (m/s2) Default is 0.0. +- **jerk** (_float_) +Desired jerk (m/s3). Default is 0.0. + +### Methods +- **\__init__**(**self**, **steer**=0.0, **steer_speed**=0.0, **speed**=0.0, **acceleration**=0.0, **jerk**=0.0) + - **Parameters:** + - `steer` (_float_) + - `steer_speed` (_float_) + - `speed` (_float_) + - `acceleration` (_float_) + - `jerk` (_float_) + +##### Dunder methods +- **\__eq__**(**self**, **other**=[carla.AckermannVehicleControl](#carla.AckermannVehicleControl)) +- **\__ne__**(**self**, **other**=[carla.AckermannVehicleControl](#carla.AckermannVehicleControl)) +- **\__str__**(**self**) + +--- + ## carla.VehicleControl Manages the basic movement of a vehicle using typical driving controls. @@ -3033,10 +3150,6 @@ Back wheel of a 2 wheeled vehicle. Inherited from _[carla.Actor](#carla.Actor)_
This class inherits from the [carla.Actor](#carla.Actor) and defines pedestrians in the simulation. Walkers are a special type of actor that can be controlled either by an AI ([carla.WalkerAIController](#carla.WalkerAIController)) or manually via script, using a series of [carla.WalkerControl](#carla.WalkerControl) to move these and their skeletons. -### Instance Variables -- **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_) -Bounding box containing the geometry of the walker. Its location and rotation are relative to the walker it is attached to. - ### Methods - **apply_control**(**self**, **control**) On the next tick, the control will move the walker in a certain direction with a certain speed. Jumps can be commanded too. @@ -3180,13 +3293,17 @@ Waypoints in CARLA are described as 3D directed points. They have a [carla.Trans ### Instance Variables - **id** (_int_) -The identificator is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator. +The identifier is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator. - **transform** (_[carla.Transform](#carla.Transform)_) Position and orientation of the waypoint according to the current lane information. This data is computed the first time it is accessed. It is not created right away in order to ease computing costs when lots of waypoints are created but their specific transform is not needed. - **road_id** (_int_) OpenDRIVE road's id. - **section_id** (_int_) OpenDRIVE section's id, based on the order that they are originally defined. +- **is_junction** (_bool_) +True if the current Waypoint is on a junction as defined by OpenDRIVE. +- **junction_id** (_int_) +OpenDRIVE junction's id. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20). - **lane_id** (_int_) OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20). - **s** (_float_) @@ -3230,7 +3347,7 @@ Returns a list of waypoints from this to the start of the lane separated by a ce ##### Getters - **get_junction**(**self**) -If the waypoint belongs to a junction this method returns the asociated junction object. Otherwise returns null. +If the waypoint belongs to a junction this method returns the associated junction object. Otherwise returns null. - **Return:** _[carla.Junction](#carla.Junction)_ - **get_landmarks**(**self**, **distance**, **stop_at_junction**=False) Returns a list of landmarks in the road from the current waypoint until the specified distance. @@ -3440,7 +3557,7 @@ Freezes or unfreezes all traffic lights in the scene. Frozen traffic lights can - **Parameters:** - `frozen` (_bool_) - **ground_projection**(**self**, **location**, **search_distance**) -Projects the specified point downwards in the scene. The functions casts a ray from location in the direction (0,0,-1) (downwards) and returns a [carla.Labelled](#carla.Labelled) object with the first geometry this ray intersects (usually the ground). If no geometry is found in the search_distance range the function returns `None`. +Projects the specified point downwards in the scene. The functions casts a ray from location in the direction (0,0,-1) (downwards) and returns a [carla.LabelledPoint](#carla.LabelledPoint) object with the first geometry this ray intersects (usually the ground). If no geometry is found in the search_distance range the function returns `None`. - **Parameters:** - `location` (_[carla.Location](#carla.Location)_) - The point to be projected. - `search_distance` (_float_) - The maximum distance to perform the projection. @@ -3665,7 +3782,7 @@ This snapshot comprises all the information for every actor on scene at a certai ### Instance Variables - **id** (_int_) -A value unique for every snapshot to differenciate them. +A value unique for every snapshot to differentiate them. - **frame** (_int_) Simulation frame in which the snapshot was taken. - **timestamp** (_[carla.Timestamp](#carla.Timestamp) - seconds_) @@ -3817,6 +3934,23 @@ Transformation to be applied. --- +## command.ApplyVehicleAckermannControl +Command adaptation of __apply_ackermann_control()__ in [carla.Vehicle](#carla.Vehicle). Applies a certain akermann control to a vehicle. + +### Instance Variables +- **actor_id** (_int_) +Vehicle actor affected by the command. +- **control** (_[carla.AckermannVehicleControl](#carla.AckermannVehicleControl)_) +Vehicle ackermann control to be applied. + +### Methods +- **\__init__**(**self**, **actor**, **control**) + - **Parameters:** + - `actor` (_[carla.Actor](#carla.Actor) or int_) - Actor or its ID to whom the command will be applied to. + - `control` (_[carla.AckermannVehicleControl](#carla.AckermannVehicleControl)_) + +--- + ## command.ApplyVehicleControl Command adaptation of __apply_control()__ in [carla.Vehicle](#carla.Vehicle). Applies a certain control to a vehicle. @@ -3840,14 +3974,14 @@ Command adaptation of __apply_physics_control()__ i ### Instance Variables - **actor_id** (_int_) Vehicle actor affected by the command. -- **control** (_[carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl)_) +- **physics_control** (_[carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl)_) Physics control to be applied. ### Methods -- **\__init__**(**self**, **actor**, **control**) +- **\__init__**(**self**, **actor**, **physics_control**) - **Parameters:** - `actor` (_[carla.Actor](#carla.Actor) or int_) - Actor or its ID to whom the command will be applied to. - - `control` (_[carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl)_) + - `physics_control` (_[carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl)_) --- diff --git a/PythonAPI/docs/actor.yml b/PythonAPI/docs/actor.yml index 1ea4b4d0a..f87120827 100644 --- a/PythonAPI/docs/actor.yml +++ b/PythonAPI/docs/actor.yml @@ -16,10 +16,22 @@ type: int doc: > Identifier for this actor. Unique during a given episode. + - var_name: type_id + type: str + doc: > + The identifier of the blueprint this actor was based on, e.g. `vehicle.ford.mustang`. - var_name: is_alive type: bool doc: > Returns whether this object was destroyed using this actor handle. + - var_name: is_active + type: bool + doc: > + Returns whether this actor is active (True) or not (False). + - var_name: is_dormant + type: bool + doc: > + Returns whether this actor is dormant (True) or not (False) - the opposite of is_active. - var_name: parent type: carla.Actor doc: > @@ -28,10 +40,14 @@ type: list(int) doc: > A list of semantic tags provided by the blueprint listing components for this actor. E.g. a traffic light could be tagged with `Pole` and `TrafficLight`. These tags are used by the semantic segmentation sensor. Find more about this and other sensors [here](ref_sensors.md#semantic-segmentation-camera). - - var_name: type_id - type: str + - var_name: actor_state + type: carla.ActorState doc: > - The identifier of the blueprint this actor was based on, e.g. `vehicle.ford.mustang`. + Returns the carla.ActorState, which can identify if the actor is Active, Dormant or Invalid. + - var_name: bounding_box + type: carla.BoundingBox + doc: > + Bounding box containing the geometry of the actor. Its location and rotation are relative to the actor it is attached to. # - METHODS ---------------------------- methods: @@ -86,39 +102,6 @@ doc: > Disables any constant velocity previously set for a carla.Vehicle actor. # -------------------------------------- - - def_name: enable_chrono_physics - params: - - param_name: max_substeps - type: int - doc: > - Max number of Chrono substeps - - param_name: max_substep_delta_time - type: int - doc: > - Max size of substep - - param_name: vehicle_json - type: str - doc: > - Path to vehicle json file relative to `base_json_path` - - param_name: powertrain_json - type: str - doc: > - Path to powertrain json file relative to `base_json_path` - - param_name: tire_json - type: str - doc: > - Path to tire json file relative to `base_json_path` - - param_name: base_json_path - type: str - doc: > - Path to `chrono/data/vehicle` folder. E.g., `/home/user/carla/Build/chrono-install/share/chrono/data/vehicle/` (the final `/` character is required). - doc: > - Enables Chrono physics on a spawned vehicle. - note: > - Ensure that you have started the CARLA server with the `ARGS="--chrono"` flag. You will not be able to use Chrono physics without this flag set. - warning: > - Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics. - # -------------------------------------- - def_name: enable_constant_velocity params: - param_name: velocity @@ -133,36 +116,6 @@ warning: > Enabling a constant velocity for a vehicle managed by the [Traffic Manager](https://carla.readthedocs.io/en/latest/adv_traffic_manager/) may cause conflicts. This method overrides any changes in velocity by the TM. # -------------------------------------- - - def_name: show_debug_telemetry - params: - - param_name: enabled - type: bool - default: True - doc: > - Enables or disables the telemetry on this vehicle. This shows information about the vehicles current state and forces applied to it in the spectator window. Only information for one vehicle can be shown so if you enable a second one, the previous will be automatically disabled. - # -------------------------------------- - - def_name: open_door - params: - - param_name: door_idx - type: carla.VehicleDoor - doc: > - door index - doc: > - Open the door door_idx if the vehicle has it. Use carla.VehicleDoor.All to open all available doors. - note: > - Only carla.Vehicle actors can use this method. - # -------------------------------------- - - def_name: close_door - params: - - param_name: door_idx - type: carla.VehicleDoor - doc: > - door index - doc: > - Close the door door_idx if the vehicle has it. Use carla.VehicleDoor.All to close all available doors. - note: > - Only carla.Vehicle actors can use this method. - # -------------------------------------- - def_name: get_acceleration return: carla.Vector3D return_units: m/s2 @@ -244,6 +197,24 @@ doc: > Enables or disables gravity for the actor. __Default__ is True. + + - class_name: ActorState + # - DESCRIPTION ------------------------ + doc: > + Class that defines the state of an actor. + # - PROPERTIES ------------------------- + instance_variables: + - var_name: Invalid + doc: > + An actor is Invalid if a problem has occurred. + - var_name: Active + doc: > + An actor is Active when it visualized and can affect other actors. + - var_name: Dormant + doc: > + An actor is Dormant when it is not visualized and will not affect other actors through physics. For example, actors are dormant if they are on an unloaded tile in a large map. + + - class_name: VehicleLightState # - DESCRIPTION ------------------------ doc: > @@ -281,7 +252,7 @@ parent: carla.Actor # - DESCRIPTION ------------------------ doc: > - One of the most important group of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in carla.BlueprintLibrary to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the traffic manager. + One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in carla.BlueprintLibrary to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the traffic manager. # - PROPERTIES ------------------------- instance_variables: - var_name: bounding_box @@ -295,7 +266,28 @@ - param_name: control type: carla.VehicleControl doc: > - Applies a control object on the next tick, containing driving parameters such as throttle, steering or gear shifting. + Applies a control object on the next tick, containing driving parameters such as throttle, steering or gear shifting. + # -------------------------------------- + - def_name: apply_ackermann_control + params: + - param_name: control + type: carla.VehicleAckermannControl + doc: > + Applies an Ackermann control object on the next tick. + # -------------------------------------- + - def_name: apply_ackermann_controller_settings + params: + - param_name: settings + type: carla.AckermannControllerSettings + doc: > + Applies a new Ackermann control settings to this vehicle in the next tick. + warning: This method does call the simulator. + # -------------------------------------- + - def_name: get_ackermann_controller_settings + return: carla.AckermannControllerSettings + doc: > + Returns the last Ackermann control settings applied to this vehicle. + warning: This method does call the simulator to retrieve the value. # -------------------------------------- - def_name: apply_physics_control params: @@ -360,6 +352,39 @@ doc: > Enables or disables the usage of CarSim vs terrain file specified in the `.simfile`. By default this option is disabled and CarSim uses unreal engine methods to process the geometry of the scene. # -------------------------------------- + - def_name: enable_chrono_physics + params: + - param_name: max_substeps + type: int + doc: > + Max number of Chrono substeps + - param_name: max_substep_delta_time + type: int + doc: > + Max size of substep + - param_name: vehicle_json + type: str + doc: > + Path to vehicle json file relative to `base_json_path` + - param_name: powertrain_json + type: str + doc: > + Path to powertrain json file relative to `base_json_path` + - param_name: tire_json + type: str + doc: > + Path to tire json file relative to `base_json_path` + - param_name: base_json_path + type: str + doc: > + Path to `chrono/data/vehicle` folder. E.g., `/home/user/carla/Build/chrono-install/share/chrono/data/vehicle/` (the final `/` character is required). + doc: > + Enables Chrono physics on a spawned vehicle. + note: > + Ensure that you have started the CARLA server with the `ARGS="--chrono"` flag. You will not be able to use Chrono physics without this flag set. + warning: > + Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics. + # -------------------------------------- - def_name: set_autopilot params: - param_name: enabled @@ -408,6 +433,31 @@ doc: > Vehicle have failure states, to indicate that it is incapable of continuing its route. This function returns the vehicle's specific failure state, or in other words, the cause that resulted in it. # -------------------------------------- + - def_name: show_debug_telemetry + params: + - param_name: enabled + type: bool + default: True + doc: > + Enables or disables the telemetry on this vehicle. This shows information about the vehicles current state and forces applied to it in the spectator window. Only information for one vehicle can be shown so that, if you enable a second one, the previous will be automatically disabled. + # -------------------------------------- + - def_name: open_door + params: + - param_name: door_idx + type: carla.VehicleDoor + doc: > + door index + doc: > + Open the door `door_idx` if the vehicle has it. Use carla.VehicleDoor.All to open all available doors. + # -------------------------------------- + - def_name: close_door + params: + - param_name: door_idx + type: carla.VehicleDoor + doc: > + door index + doc: > + Close the door `door_idx` if the vehicle has it. Use carla.VehicleDoor.All to close all available doors. - class_name: Walker @@ -416,11 +466,6 @@ doc: > This class inherits from the carla.Actor and defines pedestrians in the simulation. Walkers are a special type of actor that can be controlled either by an AI (carla.WalkerAIController) or manually via script, using a series of carla.WalkerControl to move these and their skeletons. # - PROPERTIES ------------------------- - instance_variables: - - var_name: bounding_box - type: carla.BoundingBox - doc: > - Bounding box containing the geometry of the walker. Its location and rotation are relative to the walker it is attached to. # - METHODS ---------------------------- methods: - def_name: apply_control @@ -669,6 +714,8 @@ # -------------------------------------- - def_name: __str__ # -------------------------------------- + + - class_name: VehicleWheelLocation doc: > `enum` representing the position of each wheel on a vehicle. @@ -694,6 +741,7 @@ doc: > Back wheel of a 2 wheeled vehicle. # -------------------------------------- + - class_name: VehicleDoor doc: > Possible index representing the possible doors that can be open. diff --git a/PythonAPI/docs/blueprint.yml b/PythonAPI/docs/blueprint.yml index 4c58d44f5..01532ea5b 100644 --- a/PythonAPI/docs/blueprint.yml +++ b/PythonAPI/docs/blueprint.yml @@ -327,6 +327,7 @@ doc: > Filters a list of blueprints matching the `wildcard_pattern` against the id and tags of every blueprint contained in this library and returns the result as a new one. Matching follows [fnmatch](https://docs.python.org/2/library/fnmatch.html) standard. return: carla.BlueprintLibrary + # -------------------------------------- - def_name: filter_by_attribute params: - param_name: name diff --git a/PythonAPI/docs/client.yml b/PythonAPI/docs/client.yml index 69f5c9008..35c968e9a 100644 --- a/PythonAPI/docs/client.yml +++ b/PythonAPI/docs/client.yml @@ -305,6 +305,13 @@ type: bool doc: > Enables or disables playback of the hero vehicle during a playback of a recorded simulation. + # -------------------------------------- + - def_name: set_replayer_ignore_spectator + params: + - param_name: ignore_spectator + type: bool + doc: > + Determines whether the recorded spectator movements will be replicated by the replayer. # -------------------------------------- - def_name: set_files_base_folder params: @@ -717,6 +724,10 @@ doc: > Adjust probability that in each timestep the actor will perform a right lane change, dependent on lane change availability. # -------------------------------------- + - def_name: shut_down + doc: > + Shuts down the traffic manager. + # -------------------------------------- - class_name: OpendriveGenerationParameters # - DESCRIPTION ------------------------ diff --git a/PythonAPI/docs/commands.yml b/PythonAPI/docs/commands.yml index f97cf0ed0..cf7307681 100644 --- a/PythonAPI/docs/commands.yml +++ b/PythonAPI/docs/commands.yml @@ -101,7 +101,7 @@ type: int doc: > Vehicle actor affected by the command. - - var_name: control + - var_name: physics_control type: carla.VehiclePhysicsControl doc: > Physics control to be applied. @@ -113,7 +113,7 @@ type: carla.Actor or int doc: > Actor or its ID to whom the command will be applied to. - - param_name: control + - param_name: physics_control type: carla.VehiclePhysicsControl # -------------------------------------- @@ -143,6 +143,32 @@ type: carla.VehicleControl # -------------------------------------- + - class_name: ApplyVehicleAckermannControl + # - DESCRIPTION ------------------------ + doc: > + Command adaptation of __apply_ackermann_control()__ in carla.Vehicle. Applies a certain akermann control to a vehicle. + # - PROPERTIES ------------------------- + instance_variables: + - var_name: actor_id + type: int + doc: > + Vehicle actor affected by the command. + - var_name: control + type: carla.AckermannVehicleControl + doc: > + Vehicle ackermann control to be applied. + # - METHODS ---------------------------- + methods: + - def_name: __init__ + params: + - param_name: actor + type: carla.Actor or int + doc: > + Actor or its ID to whom the command will be applied to. + - param_name: control + type: carla.AckermannVehicleControl + # -------------------------------------- + - class_name: ApplyWalkerControl # - DESCRIPTION ------------------------ doc: > diff --git a/PythonAPI/docs/control.yml b/PythonAPI/docs/control.yml index a0676a0bc..d54d2c09b 100644 --- a/PythonAPI/docs/control.yml +++ b/PythonAPI/docs/control.yml @@ -86,6 +86,140 @@ - def_name: __str__ # -------------------------------------- + - class_name: VehicleAckermannControl + # - DESCRIPTION ------------------------ + doc: > + Manages the basic movement of a vehicle using Ackermann driving controls. + # - PROPERTIES ------------------------- + instance_variables: + - var_name: steer + type: float + doc: > + Desired steer (rad). Positive value is to the right. Default is 0.0. + # -------------------------------------- + - var_name: steer_speed + type: float + doc: > + Steering velocity (rad/s). Zero steering angle velocity means change the steering angle as quickly as possible. Default is 0.0. + # -------------------------------------- + - var_name: speed + type: float + doc: > + Desired speed (m/s). Default is 0.0. + # -------------------------------------- + - var_name: acceleration + type: float + doc: > + Desired acceleration (m/s2) Default is 0.0. + # -------------------------------------- + - var_name: jerk + type: float + doc: > + Desired jerk (m/s3). Default is 0.0. + # - METHODS ---------------------------- + methods: + - def_name: __init__ + params: + - param_name: steer + type: float + default: 0.0 + - param_name: steer_speed + type: float + default: 0.0 + - param_name: speed + type: float + default: 0.0 + - param_name: acceleration + type: float + default: 0.0 + - param_name: jerk + type: float + default: 0.0 + # -------------------------------------- + - def_name: __eq__ + params: + - param_name: other + type: carla.AckermannVehicleControl + # -------------------------------------- + - def_name: __ne__ + params: + - param_name: other + type: carla.AckermannVehicleControl + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + + - class_name: AckermannControllerSettings + # - DESCRIPTION ------------------------ + doc: > + Manages the settings of the Ackermann PID controller. + # - PROPERTIES ------------------------- + instance_variables: + - var_name: speed_kp + type: float + doc: > + Proportional term of the speed PID controller. + # -------------------------------------- + - var_name: speed_ki + type: float + doc: > + Integral term of the speed PID controller. + # -------------------------------------- + - var_name: speed_kd + type: float + doc: > + Derivative term of the speed PID controller. + # -------------------------------------- + - var_name: accel_kp + type: float + doc: > + Proportional term of the acceleration PID controller. + # -------------------------------------- + - var_name: accel_ki + type: float + doc: > + Integral term of the acceleration PID controller. + # -------------------------------------- + - var_name: accel_kd + type: float + doc: > + Derivative term of the acceleration PID controller. + # - METHODS ---------------------------- + methods: + - def_name: __init__ + params: + - param_name: speed_kp + type: float + default: 0.15 + - param_name: speed_ki + type: float + default: 0.0 + - param_name: speed_kd + type: float + default: 0.25 + - param_name: accel_kp + type: float + default: 0.01 + - param_name: accel_ki + type: float + default: 0.0 + - param_name: accel_kd + type: float + default: 0.01 + # -------------------------------------- + - def_name: __eq__ + params: + - param_name: other + type: carla.AckermannControllerSettings + # -------------------------------------- + - def_name: __ne__ + params: + - param_name: other + type: carla.AckermannControllerSettings + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + - class_name: WalkerControl doc: > This class defines specific directions that can be commanded to a carla.Walker to control it via script. diff --git a/PythonAPI/docs/geom.yml b/PythonAPI/docs/geom.yml index 05b1092e2..eb71836e4 100644 --- a/PythonAPI/docs/geom.yml +++ b/PythonAPI/docs/geom.yml @@ -192,6 +192,14 @@ doc: > Computes the 2-dimensional squared distance between two vectors. # -------------------------------------- + - def_name: get_vector_angle + return: float + params: + - param_name: vector + type: carla.Vector3D + doc: > + Computes the angle between a pair of 3D vectors in radians. + # -------------------------------------- - def_name: __add__ params: - param_name: other @@ -436,6 +444,15 @@ doc: > Translates a 3D point from local to global coordinates using the current transformation as frame of reference. # -------------------------------------- + - def_name: transform_vector + params: + - param_name: in_vector + type: carla.Vector3D + doc: > + Vector to which the transformation will be applied. + doc: > + Rotates a vector using the current transformation as frame of reference, without applying translation. Use this to transform, for example, a velocity. + # -------------------------------------- - def_name: get_forward_vector return: carla.Vector3D doc: > @@ -444,7 +461,7 @@ - def_name: get_right_vector return: carla.Vector3D doc: > - Computes a right vector using the rotatio of the object. + Computes a right vector using the rotation of the object. # -------------------------------------- - def_name: get_up_vector return: carla.Vector3D diff --git a/PythonAPI/docs/map.yml b/PythonAPI/docs/map.yml index 3b4d0929d..fa8e261de 100644 --- a/PythonAPI/docs/map.yml +++ b/PythonAPI/docs/map.yml @@ -275,6 +275,15 @@ Returns a list of locations with all crosswalk zones in the form of closed polygons. The first point is repeated, symbolizing where the polygon begins and ends. return: list(carla.Location) # -------------------------------------- + - def_name: cook_in_memory_map + params: + - param_name: path + type: str + doc: > + Path to the intended location of the stored binary map file. + doc: > + Generates a binary file from the CARLA map containing information used by the Traffic Manager. This method is only used during the import process for maps. + # -------------------------------------- - def_name: __str__ # -------------------------------------- @@ -313,7 +322,7 @@ - var_name: id type: int doc: > - The identificator is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator. + The identifier is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator. - var_name: transform type: carla.Transform doc: > @@ -326,6 +335,14 @@ type: int doc: > OpenDRIVE section's id, based on the order that they are originally defined. + - var_name: is_junction + type: bool + doc: > + True if the current Waypoint is on a junction as defined by OpenDRIVE. + - var_name: junction_id + type: int + doc: > + OpenDRIVE junction's id. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20) - var_name: lane_id type: int doc: > @@ -413,7 +430,7 @@ - def_name: get_junction return: carla.Junction doc: > - If the waypoint belongs to a junction this method returns the asociated junction object. Otherwise returns null. + If the waypoint belongs to a junction this method returns the associated junction object. Otherwise returns null. # -------------------------------------- - def_name: get_landmarks params: @@ -477,7 +494,7 @@ - var_name: id type: int doc: > - Identificator found in the OpenDRIVE file. + Identifier found in the OpenDRIVE file. - var_name: bounding_box type: carla.BoundingBox doc: > @@ -686,11 +703,11 @@ - var_name: type type: str doc: > - Type identificator of the landmark according to the country code. + Type identifier of the landmark according to the country code. - var_name: sub_type type: str doc: > - Subtype identificator of the landmark according to the country code. + Subtype identifier of the landmark according to the country code. - var_name: value type: float doc: > diff --git a/PythonAPI/docs/osm2odr.yml b/PythonAPI/docs/osm2odr.yml index 19871447a..dc897f618 100644 --- a/PythonAPI/docs/osm2odr.yml +++ b/PythonAPI/docs/osm2odr.yml @@ -29,6 +29,7 @@ doc: > Takes the content of an .osm file (OpenStreetMap format) and returns the content of the .xodr (OpenDRIVE format) describing said map. Some parameterization is passed to do the conversion. # -------------------------------------- + - class_name: Osm2OdrSettings # - DESCRIPTION ------------------------ doc: > diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml index 17385fb74..2915dbbfc 100644 --- a/PythonAPI/docs/sensor_data.yml +++ b/PythonAPI/docs/sensor_data.yml @@ -41,7 +41,7 @@ instance_variables: - var_name: CityScapesPalette doc: > - Converts the image to a segmentated map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera). + Converts the image to a segmented map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera). - var_name: Depth doc: > Converts the image to a linear depth map. Used by the [depth camera](ref_sensors.md#depth-camera). @@ -106,6 +106,8 @@ Image width in pixels. - var_name: raw_data type: bytes + doc: > + Flattened array of pixel data, use reshape to create an image array. # - METHODS ---------------------------- methods: - def_name: convert @@ -172,6 +174,8 @@ Image width in pixels. - var_name: raw_data type: bytes + doc: > + Flattened array of pixel data, use reshape to create an image array. # - METHODS ---------------------------- methods: - def_name: get_color_coded_flow @@ -221,7 +225,7 @@ - var_name: raw_data type: bytes doc: > - Received list of 4D points. Each point consists of [x,y,z] coordiantes plus the intensity computed for that point. + Received list of 4D points. Each point consists of [x,y,z] coordinates plus the intensity computed for that point. # - METHODS ---------------------------- methods: - def_name: save_to_disk @@ -263,7 +267,7 @@ - class_name: LidarDetection # - DESCRIPTION ------------------------ doc: > - Data contained inside a carla.LidarMeasurement. Each of these represents one of the points in the cloud with its location and its asociated intensity. + Data contained inside a carla.LidarMeasurement. Each of these represents one of the points in the cloud with its location and its associated intensity. # - PROPERTIES ------------------------- instance_variables: - var_name: point @@ -613,6 +617,7 @@ Part of the data contained inside a carla.RssResponse describing the state of the vehicle. The parameters include its current dynamics, and how it is heading regarding the target route. # - PROPERTIES ------------------------- instance_variables: + ## ** Missing timestamp and time_since_epoch_check_start_ms - var_name: ego_speed type: ad.physics.Speed doc: > diff --git a/PythonAPI/docs/snapshot.yml b/PythonAPI/docs/snapshot.yml index d9a121ec3..9a9c7f2e6 100644 --- a/PythonAPI/docs/snapshot.yml +++ b/PythonAPI/docs/snapshot.yml @@ -12,7 +12,7 @@ - var_name: id type: int doc: > - A value unique for every snapshot to differenciate them. + A value unique for every snapshot to differentiate them. - var_name: frame type: int doc: > diff --git a/PythonAPI/docs/world.yml b/PythonAPI/docs/world.yml index c354b6921..427940287 100644 --- a/PythonAPI/docs/world.yml +++ b/PythonAPI/docs/world.yml @@ -278,7 +278,7 @@ instance_variables: - var_name: Rigid doc: > - With this fixed attatchment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation. + With this fixed attachment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation. - var_name: SpringArm doc: > An attachment that expands or retracts the position of the actor, depending on its parent. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so [check the UE docs](https://docs.unrealengine.com/en-US/Gameplay/HowTo/UsingCameras/SpringArmComponents/index.html) to learn more about them.
Warning: The SpringArm attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. child_location = Location(0,0,2)). @@ -790,7 +790,7 @@ doc: > The maximum distance to perform the projection doc: > - Projects the specified point downwards in the scene. The functions casts a ray from location in the direction (0,0,-1) (downwards) and returns a carla.Labelled object with the first geometry this ray intersects (usually the ground). If no geometry is found in the search_distance range the function returns `None`. + Projects the specified point downwards in the scene. The functions casts a ray from location in the direction (0,0,-1) (downwards) and returns a carla.LabelledPoint object with the first geometry this ray intersects (usually the ground). If no geometry is found in the search_distance range the function returns `None`. # -------------------------------------- - def_name: load_map_layer params: