diff --git a/Docs/python_api.md b/Docs/python_api.md index a923880cc..54ccbac0e 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -527,7 +527,8 @@ Sets the maxixum time a network call is allowed before blocking it and raising a --- ## carla.CollisionEvent -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines a collision data for sensor.other.collision. The sensor creates one of this for every collision detected which may be many for one simulation step. Learn more about this [here](ref_sensors.md#collision-detector). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines a collision data for sensor.other.collision. The sensor creates one of this for every collision detected which may be many for one simulation step. Learn more about this [here](ref_sensors.md#collision-detector). ### Instance Variables - **actor** (_[carla.Actor](#carla.Actor)_) @@ -761,7 +762,8 @@ Height regarding ground level. --- ## carla.GnssMeasurement -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the Gnss data registered by a sensor.other.gnss. It essentially reports its position with the position of the sensor and an OpenDRIVE geo-reference. +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the Gnss data registered by a sensor.other.gnss. It essentially reports its position with the position of the sensor and an OpenDRIVE geo-reference. ### Instance Variables - **altitude** (_float – meters_) @@ -779,7 +781,8 @@ West/East value of a point on the map. --- ## carla.IMUMeasurement -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the data registered by a sensor.other.imu, regarding the sensor's transformation according to the current [carla.World](#carla.World). It essentially acts as accelerometer, gyroscope and compass. +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the data registered by a sensor.other.imu, regarding the sensor's transformation according to the current [carla.World](#carla.World). It essentially acts as accelerometer, gyroscope and compass. ### Instance Variables - **accelerometer** (_[carla.Vector3D](#carla.Vector3D) – m/s2_) @@ -797,7 +800,8 @@ Angular velocity. --- ## carla.Image -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines an image of 32-bit BGRA colors that will be used as initial data retrieved by camera sensors. There are different camera sensors (currently three, RGB, depth and semantic segmentation) and each of these makes different use for the images. Learn more about them [here](ref_sensors.md). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines an image of 32-bit BGRA colors that will be used as initial data retrieved by camera sensors. There are different camera sensors (currently three, RGB, depth and semantic segmentation) and each of these makes different use for the images. Learn more about them [here](ref_sensors.md). ### Instance Variables - **fov** (_float – degrees_) @@ -1026,7 +1030,8 @@ Traffic rules allow turning either right or left. --- ## carla.LaneInvasionEvent -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines lanes invasion for sensor.other.lane_invasion. It works only client-side and is dependant on OpenDRIVE to provide reliable information. The sensor creates one of this every time there is a lane invasion, which may be more than once per simulation step. Learn more about this [here](ref_sensors.md#lane-invasion-detector). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines lanes invasion for sensor.other.lane_invasion. It works only client-side and is dependant on OpenDRIVE to provide reliable information. The sensor creates one of this every time there is a lane invasion, which may be more than once per simulation step. Learn more about this [here](ref_sensors.md#lane-invasion-detector). ### Instance Variables - **actor** (_[carla.Actor](#carla.Actor)_) @@ -1136,7 +1141,8 @@ Computed intensity for this point as a scalar value between [0.0 , 1.0]. --- ## carla.LidarMeasurement -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the LIDAR data retrieved by a sensor.lidar.ray_cast. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#lidar-raycast-sensor). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the LIDAR data retrieved by a sensor.lidar.ray_cast. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#lidar-raycast-sensor). ### Instance Variables - **channels** (_int_) @@ -1145,6 +1151,8 @@ Number of lasers shot. 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. +- **horizontal_fov** (_float – degrees, between 0 and 180_) +Horizontal field of view of the image. ### Methods - **save_to_disk**(**self**, **path**) @@ -1367,7 +1375,8 @@ Switch of a light. It is __True__ when the light is on. --- ## carla.Location -
Inherited from _[carla.Vector3D](#carla.Vector3D)_
Represents a spot in the world. +Inherited from _[carla.Vector3D](#carla.Vector3D)_
+Represents a spot in the world. ### Instance Variables - **x** (_float – meters_) @@ -1501,7 +1510,8 @@ All layers selected. --- ## carla.ObstacleDetectionEvent -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the obstacle data for sensor.other.obstacle. Learn more about this [here](ref_sensors.md#obstacle-detector). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the obstacle data for sensor.other.obstacle. Learn more about this [here](ref_sensors.md#obstacle-detector). ### Instance Variables - **actor** (_[carla.Actor](#carla.Actor)_) @@ -1590,7 +1600,8 @@ The velocity of the detected object towards the sensor. --- ## carla.RadarMeasurement -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines and gathers the measures registered by a sensor.other.radar, representing a wall of points in front of the sensor with a distance, angle and velocity in relation to it. The data consists of a [carla.RadarDetection](#carla.RadarDetection) array. Learn more about this [here](ref_sensors.md#radar-sensor). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines and gathers the measures registered by a sensor.other.radar, representing a wall of points in front of the sensor with a distance, angle and velocity in relation to it. The data consists of a [carla.RadarDetection](#carla.RadarDetection) array. Learn more about this [here](ref_sensors.md#radar-sensor). ### Instance Variables - **raw_data** (_bytes_) @@ -1756,7 +1767,8 @@ Enum declaration used in [carla.RssSensor](#carla.RssSensor) to set the log leve --- ## carla.RssResponse -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that contains the output of a [carla.RssSensor](#carla.RssSensor). This is the result of the RSS calculations performed for the parent vehicle of the sensor. +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that contains the output of a [carla.RssSensor](#carla.RssSensor). This is the result of the RSS calculations performed for the parent vehicle of the sensor. A [carla.RssRestrictor](#carla.RssRestrictor) will use the data to modify the [carla.VehicleControl](#carla.VehicleControl) of the vehicle. @@ -1808,7 +1820,8 @@ Disables the _stay on road_ feature. --- ## carla.RssSensor -
Inherited from _[carla.Sensor](#carla.Sensor)_
This sensor works a bit differently than the rest. Take look at the [specific documentation](adv_rss.md), and the [rss sensor reference](ref_sensors.md#rss-sensor) to gain full understanding of it. +Inherited from _[carla.Sensor](#carla.Sensor)_
+This sensor works a bit differently than the rest. Take look at the [specific documentation](adv_rss.md), and the [rss sensor reference](ref_sensors.md#rss-sensor) to gain full understanding of it. The RSS sensor uses world information, and a [RSS library](https://github.com/intel/ad-rss-lib) to make safety checks on a vehicle. The output retrieved by the sensor is a [carla.RssResponse](#carla.RssResponse). This will be used by a [carla.RssRestrictor](#carla.RssRestrictor) to modify a [carla.VehicleControl](#carla.VehicleControl) before applying it to a vehicle. @@ -1874,7 +1887,8 @@ ID of the actor hit by the ray. --- ## carla.SemanticLidarMeasurement -
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the semantic LIDAR data retrieved by a sensor.lidar.ray_cast_semantic. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#semanticlidar-raycast-sensor). +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the semantic LIDAR data retrieved by a sensor.lidar.ray_cast_semantic. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#semanticlidar-raycast-sensor). ### Instance Variables - **channels** (_int_) @@ -1883,6 +1897,8 @@ Number of lasers shot. Horizontal angle the LIDAR is rotated at the time of the measurement. - **raw_data** (_bytes_) Received list of raw detection points. Each point consists of [x,y,z] coordinates plus the cosine of the incident angle, the index of the hit actor, and its semantic tag. +- **horizontal_fov** (_float – degrees, between 0 and 180_) +Horizontal field of view of the image. ### Methods - **save_to_disk**(**self**, **path**) @@ -1907,7 +1923,8 @@ Iterate over the [carla.SemanticLidarDetection](#carla.SemanticLidarDetection) r --- ## carla.Sensor -
Inherited from _[carla.Actor](#carla.Actor)_
Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at [carla.World](#carla.World) to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from [carla.SensorData](#carla.SensorData) (depending on the sensor). +Inherited from _[carla.Actor](#carla.Actor)_
+Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at [carla.World](#carla.World) to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from [carla.SensorData](#carla.SensorData) (depending on the sensor). Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow.
Receive data on every tick. @@ -1994,7 +2011,8 @@ Time register of the frame at which this measurement was taken given by the OS i --- ## carla.TrafficLight -
Inherited from _[carla.TrafficSign](#carla.TrafficSign)_
A traffic light actor, considered a specific type of traffic sign. As traffic lights will mostly appear at junctions, they belong to a group which contains the different traffic lights in it. Inside the group, traffic lights are differenciated by their pole index. +Inherited from _[carla.TrafficSign](#carla.TrafficSign)_
+A traffic light actor, considered a specific type of traffic sign. As traffic lights will mostly appear at junctions, they belong to a group which contains the different traffic lights in it. Inside the group, traffic lights are differenciated by their pole index. Within a group the state of traffic lights is changed in a cyclic pattern: one index is chosen and it spends a few seconds in green, yellow and eventually red. The rest of the traffic lights remain frozen in red this whole time, meaning that there is a gap in the last seconds of the cycle where all the traffic lights are red. However, the state of a traffic light can be changed manually. @@ -2181,7 +2199,8 @@ _ --- ## carla.TrafficSign -
Inherited from _[carla.Actor](#carla.Actor)_
Traffic signs appearing in the simulation except for traffic lights. These have their own class inherited from this in [carla.TrafficLight](#carla.TrafficLight). Right now, speed signs, stops and yields are mainly the ones implemented, but many others are borne in mind. +Inherited from _[carla.Actor](#carla.Actor)_
+Traffic signs appearing in the simulation except for traffic lights. These have their own class inherited from this in [carla.TrafficLight](#carla.TrafficLight). Right now, speed signs, stops and yields are mainly the ones implemented, but many others are borne in mind. ### Instance Variables - **trigger_volume** @@ -2306,7 +2325,8 @@ 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. +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. ### Instance Variables - **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_) @@ -2533,7 +2553,8 @@ Back wheel of a 2 wheeled vehicle. --- ## carla.Walker -
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. +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)_) @@ -2560,7 +2581,8 @@ The client returns the control applied to this walker during last tick. The meth --- ## carla.WalkerAIController -
Inherited from _[carla.Actor](#carla.Actor)_
Class that conducts AI control for a walker. The controllers are defined as actors, but they are quite different from the rest. They need to be attached to a parent actor during their creation, which is the walker they will be controlling (take a look at [carla.World](#carla.World) if you are yet to learn on how to spawn actors). They also need for a special blueprint (already defined in [carla.BlueprintLibrary](#carla.BlueprintLibrary) as "controller.ai.walker"). This is an empty blueprint, as the AI controller will be invisible in the simulation but will follow its parent around to dictate every step of the way. +Inherited from _[carla.Actor](#carla.Actor)_
+Class that conducts AI control for a walker. The controllers are defined as actors, but they are quite different from the rest. They need to be attached to a parent actor during their creation, which is the walker they will be controlling (take a look at [carla.World](#carla.World) if you are yet to learn on how to spawn actors). They also need for a special blueprint (already defined in [carla.BlueprintLibrary](#carla.BlueprintLibrary) as "controller.ai.walker"). This is an empty blueprint, as the AI controller will be invisible in the simulation but will follow its parent around to dictate every step of the way. ### Methods - **go_to_location**(**self**, **destination**) @@ -2786,6 +2808,12 @@ Maximum brake torque. Maximum handbrake torque. - **position** (_[carla.Vector3D](#carla.Vector3D)_) World position of the wheel. This is a read-only parameter. +- **long_stiff_value** (_float – kg per radian_) +Tire longitudinal stiffness per unit gravitational acceleration. +- **lat_stiff_max_load** (_float – kg per radian_) +Maximum normalized tire load at which the tire can deliver no more lateral stiffness no matter how much extra load is applied to the tire. +- **lat_stiff_value** (_float – kg per radian_) +Maximum stiffness per unit of lateral slip. ### Methods - **\__init__**(**self**, **tire_friction**=2.0, **damping_rate**=0.25, **max_steer_angle**=70.0, **radius**=30.0, **max_brake_torque**=1500.0, **max_handbrake_torque**=3000.0, **position**=(0.0,0.0,0.0)) diff --git a/Docs/tuto_G_control_vehicle_physics.md b/Docs/tuto_G_control_vehicle_physics.md index 41eb51769..7135b5086 100644 --- a/Docs/tuto_G_control_vehicle_physics.md +++ b/Docs/tuto_G_control_vehicle_physics.md @@ -1,8 +1,7 @@ # How to control vehicle physics -Physics properties can be tuned for vehicles and its wheels. -These changes are applied **only** on runtime, and values are set back to default ones when -the execution ends. +Physics properties can be tuned for vehicles and their wheels. +These changes are applied **only** on runtime, and values are set back to default when the execution ends. These properties are controlled through a [carla.VehiclePhysicsControl](python_api.md#carla.VehiclePhysicsControl) object, @@ -23,17 +22,16 @@ def main(): # Get World and Actors world = client.get_world() - current_map = world.get_map() actors = world.get_actors() # Get a random vehicle from world (there should be one at least) vehicle = random.choice([actor for actor in actors if 'vehicle' in actor.type_id]) # Create Wheels Physics Control - front_left_wheel = carla.WheelPhysicsControl(tire_friction=4.5, damping_rate=1.0, max_steer_angle=70.0, radius=30.0) - front_right_wheel = carla.WheelPhysicsControl(tire_friction=2.5, damping_rate=1.5, max_steer_angle=70.0, radius=25.0) - rear_left_wheel = carla.WheelPhysicsControl(tire_friction=1.0, damping_rate=0.2, max_steer_angle=0.0, radius=15.0) - rear_right_wheel = carla.WheelPhysicsControl(tire_friction=1.5, damping_rate=1.3, max_steer_angle=0.0, radius=20.0) + front_left_wheel = carla.WheelPhysicsControl(tire_friction=2.0, damping_rate=1.5, max_steer_angle=70.0, long_stiff_value=1000) + front_right_wheel = carla.WheelPhysicsControl(tire_friction=2.0, damping_rate=1.5, max_steer_angle=70.0, long_stiff_value=1000) + rear_left_wheel = carla.WheelPhysicsControl(tire_friction=3.0, damping_rate=1.5, max_steer_angle=0.0, long_stiff_value=1000) + rear_right_wheel = carla.WheelPhysicsControl(tire_friction=3.0, damping_rate=1.5, max_steer_angle=0.0, long_stiff_value=1000) wheels = [front_left_wheel, front_right_wheel, rear_left_wheel, rear_right_wheel] @@ -50,11 +48,12 @@ def main(): physics_control.mass = 10000 physics_control.drag_coefficient = 0.25 physics_control.steering_curve = [carla.Vector2D(x=0, y=1), carla.Vector2D(x=100, y=1), carla.Vector2D(x=300, y=1)] - physics_control.wheels = wheels physics_control.use_sweep_wheel_collision = True + physics_control.wheels = wheels # Apply Vehicle Physics Control for the vehicle vehicle.apply_physics_control(physics_control) + print(physics_control) if __name__ == '__main__': main() diff --git a/PythonAPI/docs/control.yml b/PythonAPI/docs/control.yml index cf62e3a22..f52be3efd 100644 --- a/PythonAPI/docs/control.yml +++ b/PythonAPI/docs/control.yml @@ -423,6 +423,27 @@ type: carla.Vector3D doc: > World position of the wheel. This is a read-only parameter. + # -------------------------------------- + - var_name: long_stiff_value + type: float + var_units: kg per radian + default: 1000 + doc: > + Tire longitudinal stiffness per unit gravitational acceleration. + # -------------------------------------- + - var_name: lat_stiff_max_load + type: float + var_units: kg per radian + default: 2 + doc: > + Maximum normalized tire load at which the tire can deliver no more lateral stiffness no matter how much extra load is applied to the tire. + # -------------------------------------- + - var_name: lat_stiff_value + type: float + var_units: kg per radian + default: 17 + doc: > + Maximum stiffness per unit of lateral slip. # - METHODS ---------------------------- methods: - def_name: __init__ diff --git a/PythonAPI/docs/doc_gen.py b/PythonAPI/docs/doc_gen.py index 5b350aad9..694b532dd 100755 --- a/PythonAPI/docs/doc_gen.py +++ b/PythonAPI/docs/doc_gen.py @@ -91,7 +91,7 @@ class MarkdownFile: def inherit_join(self, inh): self._data = join([ - self._data,'
Inherited from ',inh,'
']) + self._data, 'Inherited from ', inh, '
\n']) def note(self, buf): self._data = join([self._data, buf]) diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml index 9672c106f..86886741f 100644 --- a/PythonAPI/docs/sensor_data.yml +++ b/PythonAPI/docs/sensor_data.yml @@ -161,15 +161,23 @@ type: int doc: > Number of lasers shot. + # -------------------------------------- - var_name: horizontal_angle type: float var_units: radians doc: > Horizontal angle the LIDAR is rotated at the time of the measurement. + # -------------------------------------- - 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. + # -------------------------------------- + - var_name: horizontal_fov + type: float + var_units: degrees, between 0 and 180 + doc: > + Horizontal field of view of the image. # - METHODS ---------------------------- methods: - def_name: save_to_disk @@ -239,15 +247,23 @@ type: int doc: > Number of lasers shot. + # -------------------------------------- - var_name: horizontal_angle type: float var_units: radians doc: > Horizontal angle the LIDAR is rotated at the time of the measurement. + # -------------------------------------- - var_name: raw_data type: bytes doc: > Received list of raw detection points. Each point consists of [x,y,z] coordinates plus the cosine of the incident angle, the index of the hit actor, and its semantic tag. + # -------------------------------------- + - var_name: horizontal_fov + type: float + var_units: degrees, between 0 and 180 + doc: > + Horizontal field of view of the image. # - METHODS ---------------------------- methods: - def_name: save_to_disk