Corkyw10/chrono docs (#4160)
* Added Chrono Integration page to navigation * Initial draft of Chrono documentation * Added Python API information for enable_chrono_physics. Made some syntactical changes to first draft of Chrono docs. * Made the forward slash character in PythonAPI stand out. Added link to Actor class in the Chrono doc. * Added manual_control_chrono.py to PythonAPI/examples * Edited chrono torial. Edited changelog. Co-authored-by: Axel <axellopez92@outlook.com>
This commit is contained in:
parent
ad860c3d1a
commit
cec8fd90ae
|
@ -13,6 +13,8 @@
|
|||
* Added optional flag to `client.replay_file()` `replay_sensors` to enable or disable the replaying the sensors
|
||||
* Improved manual_control: now cameras are set in relation with car size
|
||||
* Added CHRONO library for vehicle dynamics simulation (https://projectchrono.org/)
|
||||
- Supported JSON vehicle definition
|
||||
- Unsupported collision dynamics
|
||||
* Added performance benchmarking section to documentation
|
||||
* CARLA is compatible with the last RoadRunner nomenclature for road assets
|
||||
* Fixed a bug when importing a FBX map with some **_** in the FBX name
|
||||
|
|
|
@ -42,10 +42,25 @@ Tells the simulator to destroy this actor and returns <b>True</b> if it was succ
|
|||
_</font>
|
||||
- <a name="carla.Actor.disable_constant_velocity"></a>**<font color="#7fb800">disable_constant_velocity</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Disables any constant velocity previously set for a [carla.Vehicle](#carla.Vehicle) actor.
|
||||
- <a name="carla.Actor.enable_chrono_physics"></a>**<font color="#7fb800">enable_chrono_physics</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**max_substeps**</font>, <font color="#00a6ed">**max_substep_delta_time**</font>, <font color="#00a6ed">**vehicle_json**</font>, <font color="#00a6ed">**powertrain_json**</font>, <font color="#00a6ed">**tire_json**</font>, <font color="#00a6ed">**base_json_path**</font>)
|
||||
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:** <font color="#8E8E8E">_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.
|
||||
_</font>
|
||||
- **Warning:** <font color="#ED2F2F">_Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics.
|
||||
_</font>
|
||||
- <a name="carla.Actor.enable_constant_velocity"></a>**<font color="#7fb800">enable_constant_velocity</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**velocity**</font>)
|
||||
Sets a vehicle's velocity vector to a constant value over time. The resulting velocity will be approximately the `velocity` being set, as with __<font color="#7fb800">set_target_velocity()</font>__.
|
||||
- **Parameters:**
|
||||
- `velocity` (_[carla.Vector3D](#carla.Vector3D)<small> – m/s</small>_) – Velocity vector in local space.
|
||||
- **Note:** <font color="#8E8E8E">_Only [carla.Vehicle](#carla.Vehicle) actors can use this method.
|
||||
_</font>
|
||||
- **Warning:** <font color="#ED2F2F">_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.
|
||||
_</font>
|
||||
|
||||
|
@ -3378,146 +3393,37 @@ world.load_map_layer(carla.MapLayer.ParkedVehicles)
|
|||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.unload_map_layer-snipet" style="display: none;">
|
||||
<div id ="carla.ActorBlueprint.set_attribute-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.unload_map_layer
|
||||
Snippet for carla.ActorBlueprint.set_attribute
|
||||
</p>
|
||||
<div id="carla.World.unload_map_layer-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# This recipe toggles off several layers in our "_Opt" maps
|
||||
|
||||
# Load town one with minimum layout (roads, sidewalks, traffic lights and traffic signs)
|
||||
# as well as buildings and parked vehicles
|
||||
world = client.load_world('Town01_Opt', carla.MapLayer.Buildings | carla.MapLayer.ParkedVehicles)
|
||||
|
||||
# Toggle all buildings off
|
||||
world.unload_map_layer(carla.MapLayer.Buildings)
|
||||
|
||||
# Toggle all parked vehicles off
|
||||
world.unload_map_layer(carla.MapLayer.ParkedVehicles)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.unload_map_layer-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Map.get_waypoint-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Map.get_waypoint
|
||||
</p>
|
||||
<div id="carla.Map.get_waypoint-code" class="SnipetContent">
|
||||
<div id="carla.ActorBlueprint.set_attribute-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe shows the current traffic rules affecting the vehicle.
|
||||
# Shows the current lane type and if a lane change can be done in the actual lane or the surrounding ones.
|
||||
# This recipe changes attributes of different type of blueprint actors.
|
||||
|
||||
# ...
|
||||
waypoint = world.get_map().get_waypoint(vehicle.get_location(),project_to_road=True, lane_type=(carla.LaneType.Driving | carla.LaneType.Shoulder | carla.LaneType.Sidewalk))
|
||||
print("Current lane type: " + str(waypoint.lane_type))
|
||||
# Check current lane change allowed
|
||||
print("Current Lane change: " + str(waypoint.lane_change))
|
||||
# Left and Right lane markings
|
||||
print("L lane marking type: " + str(waypoint.left_lane_marking.type))
|
||||
print("L lane marking change: " + str(waypoint.left_lane_marking.lane_change))
|
||||
print("R lane marking type: " + str(waypoint.right_lane_marking.type))
|
||||
print("R lane marking change: " + str(waypoint.right_lane_marking.lane_change))
|
||||
walker_bp = world.get_blueprint_library().filter('walker.pedestrian.0002')
|
||||
walker_bp.set_attribute('is_invincible', True)
|
||||
|
||||
# ...
|
||||
# Changes attribute randomly by the recommended value
|
||||
vehicle_bp = wolrd.get_blueprint_library().filter('vehicle.bmw.*')
|
||||
color = random.choice(vehicle_bp.get_attribute('color').recommended_values)
|
||||
vehicle_bp.set_attribute('color', color)
|
||||
|
||||
# ...
|
||||
|
||||
camera_bp = world.get_blueprint_library().filter('sensor.camera.rgb')
|
||||
camera_bp.set_attribute('image_size_x', 600)
|
||||
camera_bp.set_attribute('image_size_y', 600)
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Map.get_waypoint-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
|
||||
<img src="/img/snipets_images/carla.Map.get_waypoint.jpg">
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.get_spectator-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.get_spectator
|
||||
</p>
|
||||
<div id="carla.World.get_spectator-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe spawns an actor and the spectator camera at the actor's location.
|
||||
|
||||
# ...
|
||||
world = client.get_world()
|
||||
spectator = world.get_spectator()
|
||||
|
||||
vehicle_bp = random.choice(world.get_blueprint_library().filter('vehicle.bmw.*'))
|
||||
transform = random.choice(world.get_map().get_spawn_points())
|
||||
vehicle = world.try_spawn_actor(vehicle_bp, transform)
|
||||
|
||||
# Wait for world to get the vehicle actor
|
||||
world.tick()
|
||||
|
||||
world_snapshot = world.wait_for_tick()
|
||||
actor_snapshot = world_snapshot.find(vehicle.id)
|
||||
|
||||
# Set spectator at given transform (vehicle transform)
|
||||
spectator.set_transform(actor_snapshot.get_transform())
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.get_spectator-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.WalkerAIController.stop-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.WalkerAIController.stop
|
||||
</p>
|
||||
<div id="carla.WalkerAIController.stop-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
#To destroy the pedestrians, stop them from the navigation, and then destroy the objects (actor and controller).
|
||||
|
||||
# stop pedestrians (list is [controller, actor, controller, actor ...])
|
||||
for i in range(0, len(all_id), 2):
|
||||
all_actors[i].stop()
|
||||
|
||||
# destroy pedestrian (actor and controller)
|
||||
client.apply_batch([carla.command.DestroyActor(x) for x in all_id])
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.WalkerAIController.stop-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.spawn_actor-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.spawn_actor
|
||||
</p>
|
||||
<div id="carla.World.spawn_actor-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe attaches different camera / sensors to a vehicle with different attachments.
|
||||
|
||||
# ...
|
||||
camera = world.spawn_actor(rgb_camera_bp, transform, attach_to=vehicle, attachment_type=Attachment.Rigid)
|
||||
# Default attachment: Attachment.Rigid
|
||||
gnss_sensor = world.spawn_actor(sensor_gnss_bp, transform, attach_to=vehicle)
|
||||
collision_sensor = world.spawn_actor(sensor_collision_bp, transform, attach_to=vehicle)
|
||||
lane_invasion_sensor = world.spawn_actor(sensor_lane_invasion_bp, transform, attach_to=vehicle)
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.spawn_actor-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.ActorBlueprint.set_attribute-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
|
@ -3594,112 +3500,27 @@ for i in range(0, len(all_actors), 2):
|
|||
|
||||
</div>
|
||||
|
||||
<div id ="carla.ActorBlueprint.set_attribute-snipet" style="display: none;">
|
||||
<div id ="carla.WalkerAIController.stop-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.ActorBlueprint.set_attribute
|
||||
Snippet for carla.WalkerAIController.stop
|
||||
</p>
|
||||
<div id="carla.ActorBlueprint.set_attribute-code" class="SnipetContent">
|
||||
<div id="carla.WalkerAIController.stop-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe changes attributes of different type of blueprint actors.
|
||||
#To destroy the pedestrians, stop them from the navigation, and then destroy the objects (actor and controller).
|
||||
|
||||
# ...
|
||||
walker_bp = world.get_blueprint_library().filter('walker.pedestrian.0002')
|
||||
walker_bp.set_attribute('is_invincible', True)
|
||||
# stop pedestrians (list is [controller, actor, controller, actor ...])
|
||||
for i in range(0, len(all_id), 2):
|
||||
all_actors[i].stop()
|
||||
|
||||
# ...
|
||||
# Changes attribute randomly by the recommended value
|
||||
vehicle_bp = wolrd.get_blueprint_library().filter('vehicle.bmw.*')
|
||||
color = random.choice(vehicle_bp.get_attribute('color').recommended_values)
|
||||
vehicle_bp.set_attribute('color', color)
|
||||
|
||||
# ...
|
||||
|
||||
camera_bp = world.get_blueprint_library().filter('sensor.camera.rgb')
|
||||
camera_bp.set_attribute('image_size_x', 600)
|
||||
camera_bp.set_attribute('image_size_y', 600)
|
||||
# ...
|
||||
# destroy pedestrian (actor and controller)
|
||||
client.apply_batch([carla.command.DestroyActor(x) for x in all_id])
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.ActorBlueprint.set_attribute-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.DebugHelper.draw_box-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.DebugHelper.draw_box
|
||||
</p>
|
||||
<div id="carla.DebugHelper.draw_box-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe shows how to draw traffic light actor bounding boxes from a world snapshot.
|
||||
|
||||
# ....
|
||||
debug = world.debug
|
||||
world_snapshot = world.get_snapshot()
|
||||
|
||||
for actor_snapshot in world_snapshot:
|
||||
actual_actor = world.get_actor(actor_snapshot.id)
|
||||
if actual_actor.type_id == 'traffic.traffic_light':
|
||||
debug.draw_box(carla.BoundingBox(actor_snapshot.get_transform().location,carla.Vector3D(0.5,0.5,2)),actor_snapshot.get_transform().rotation, 0.05, carla.Color(255,0,0,0),0)
|
||||
# ...
|
||||
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.DebugHelper.draw_box-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
|
||||
<img src="/img/snipets_images/carla.DebugHelper.draw_box.jpg">
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Sensor.listen-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Sensor.listen
|
||||
</p>
|
||||
<div id="carla.Sensor.listen-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe applies a color conversion to the image taken by a camera sensor,
|
||||
# so it is converted to a semantic segmentation image.
|
||||
|
||||
# ...
|
||||
camera_bp = world.get_blueprint_library().filter('sensor.camera.semantic_segmentation')
|
||||
# ...
|
||||
cc = carla.ColorConverter.CityScapesPalette
|
||||
camera.listen(lambda image: image.save_to_disk('output/%06d.png' % image.frame, cc))
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Sensor.listen-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Vehicle.set_wheel_steer_direction-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Vehicle.set_wheel_steer_direction
|
||||
</p>
|
||||
<div id="carla.Vehicle.set_wheel_steer_direction-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# Sets the appearance of the vehicles front wheels to 40°. Vehicle physics will not be affected.
|
||||
|
||||
vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FR_Wheel, 40.0)
|
||||
vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FL_Wheel, 40.0)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Vehicle.set_wheel_steer_direction-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.WalkerAIController.stop-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
|
@ -3742,78 +3563,36 @@ while True:
|
|||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.enable_environment_objects-snipet" style="display: none;">
|
||||
<div id ="carla.Map.get_waypoint-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.enable_environment_objects
|
||||
Snippet for carla.Map.get_waypoint
|
||||
</p>
|
||||
<div id="carla.World.enable_environment_objects-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# This recipe turn visibility off and on for two specifc buildings on the map
|
||||
|
||||
# Get the buildings in the world
|
||||
world = client.get_world()
|
||||
env_objs = world.get_environment_objects(carla.CityObjectLabel.Buildings)
|
||||
|
||||
# Access individual building IDs and save in a set
|
||||
building_01 = env_objs[0]
|
||||
building_02 = env_objs[1]
|
||||
objects_to_toggle = {building_01.id, building_02.id}
|
||||
|
||||
# Toggle buildings off
|
||||
world.enable_environment_objects(objects_to_toggle, False)
|
||||
# Toggle buildings on
|
||||
world.enable_environment_objects(objects_to_toggle, True)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.enable_environment_objects-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Client.__init__-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Client.__init__
|
||||
</p>
|
||||
<div id="carla.Client.__init__-code" class="SnipetContent">
|
||||
<div id="carla.Map.get_waypoint-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe shows in every script provided in PythonAPI/Examples
|
||||
# and it is used to parse the client creation arguments when running the script.
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-s', '--speed',
|
||||
metavar='FACTOR',
|
||||
default=1.0,
|
||||
type=float,
|
||||
help='rate at which the weather changes (default: 1.0)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
speed_factor = args.speed
|
||||
update_freq = 0.1 / speed_factor
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
# This recipe shows the current traffic rules affecting the vehicle.
|
||||
# Shows the current lane type and if a lane change can be done in the actual lane or the surrounding ones.
|
||||
|
||||
# ...
|
||||
waypoint = world.get_map().get_waypoint(vehicle.get_location(),project_to_road=True, lane_type=(carla.LaneType.Driving | carla.LaneType.Shoulder | carla.LaneType.Sidewalk))
|
||||
print("Current lane type: " + str(waypoint.lane_type))
|
||||
# Check current lane change allowed
|
||||
print("Current Lane change: " + str(waypoint.lane_change))
|
||||
# Left and Right lane markings
|
||||
print("L lane marking type: " + str(waypoint.left_lane_marking.type))
|
||||
print("L lane marking change: " + str(waypoint.left_lane_marking.lane_change))
|
||||
print("R lane marking type: " + str(waypoint.right_lane_marking.type))
|
||||
print("R lane marking change: " + str(waypoint.right_lane_marking.lane_change))
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Client.__init__-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Map.get_waypoint-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
|
||||
<img src="/img/snipets_images/carla.Map.get_waypoint.jpg">
|
||||
|
||||
</div>
|
||||
|
||||
|
@ -3863,6 +3642,243 @@ if vehicle_actor.is_at_traffic_light():
|
|||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Vehicle.set_wheel_steer_direction-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Vehicle.set_wheel_steer_direction
|
||||
</p>
|
||||
<div id="carla.Vehicle.set_wheel_steer_direction-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# Sets the appearance of the vehicles front wheels to 40°. Vehicle physics will not be affected.
|
||||
|
||||
vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FR_Wheel, 40.0)
|
||||
vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FL_Wheel, 40.0)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Vehicle.set_wheel_steer_direction-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.DebugHelper.draw_string-snipet" style="display: none;">
|
||||
<div id ="carla.World.unload_map_layer-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.unload_map_layer
|
||||
</p>
|
||||
<div id="carla.World.unload_map_layer-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# This recipe toggles off several layers in our "_Opt" maps
|
||||
|
||||
# Load town one with minimum layout (roads, sidewalks, traffic lights and traffic signs)
|
||||
# as well as buildings and parked vehicles
|
||||
world = client.load_world('Town01_Opt', carla.MapLayer.Buildings | carla.MapLayer.ParkedVehicles)
|
||||
|
||||
# Toggle all buildings off
|
||||
world.unload_map_layer(carla.MapLayer.Buildings)
|
||||
|
||||
# Toggle all parked vehicles off
|
||||
world.unload_map_layer(carla.MapLayer.ParkedVehicles)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.unload_map_layer-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.DebugHelper.draw_box-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.DebugHelper.draw_box
|
||||
</p>
|
||||
<div id="carla.DebugHelper.draw_box-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe shows how to draw traffic light actor bounding boxes from a world snapshot.
|
||||
|
||||
# ....
|
||||
debug = world.debug
|
||||
world_snapshot = world.get_snapshot()
|
||||
|
||||
for actor_snapshot in world_snapshot:
|
||||
actual_actor = world.get_actor(actor_snapshot.id)
|
||||
if actual_actor.type_id == 'traffic.traffic_light':
|
||||
debug.draw_box(carla.BoundingBox(actor_snapshot.get_transform().location,carla.Vector3D(0.5,0.5,2)),actor_snapshot.get_transform().rotation, 0.05, carla.Color(255,0,0,0),0)
|
||||
# ...
|
||||
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.DebugHelper.draw_box-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
|
||||
<img src="/img/snipets_images/carla.DebugHelper.draw_box.jpg">
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Client.__init__-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Client.__init__
|
||||
</p>
|
||||
<div id="carla.Client.__init__-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe shows in every script provided in PythonAPI/Examples
|
||||
# and it is used to parse the client creation arguments when running the script.
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-s', '--speed',
|
||||
metavar='FACTOR',
|
||||
default=1.0,
|
||||
type=float,
|
||||
help='rate at which the weather changes (default: 1.0)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
speed_factor = args.speed
|
||||
update_freq = 0.1 / speed_factor
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Client.__init__-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Sensor.listen-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Sensor.listen
|
||||
</p>
|
||||
<div id="carla.Sensor.listen-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe applies a color conversion to the image taken by a camera sensor,
|
||||
# so it is converted to a semantic segmentation image.
|
||||
|
||||
# ...
|
||||
camera_bp = world.get_blueprint_library().filter('sensor.camera.semantic_segmentation')
|
||||
# ...
|
||||
cc = carla.ColorConverter.CityScapesPalette
|
||||
camera.listen(lambda image: image.save_to_disk('output/%06d.png' % image.frame, cc))
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Sensor.listen-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.enable_environment_objects-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.enable_environment_objects
|
||||
</p>
|
||||
<div id="carla.World.enable_environment_objects-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
# This recipe turn visibility off and on for two specifc buildings on the map
|
||||
|
||||
# Get the buildings in the world
|
||||
world = client.get_world()
|
||||
env_objs = world.get_environment_objects(carla.CityObjectLabel.Buildings)
|
||||
|
||||
# Access individual building IDs and save in a set
|
||||
building_01 = env_objs[0]
|
||||
building_02 = env_objs[1]
|
||||
objects_to_toggle = {building_01.id, building_02.id}
|
||||
|
||||
# Toggle buildings off
|
||||
world.enable_environment_objects(objects_to_toggle, False)
|
||||
# Toggle buildings on
|
||||
world.enable_environment_objects(objects_to_toggle, True)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.enable_environment_objects-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.spawn_actor-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.spawn_actor
|
||||
</p>
|
||||
<div id="carla.World.spawn_actor-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe attaches different camera / sensors to a vehicle with different attachments.
|
||||
|
||||
# ...
|
||||
camera = world.spawn_actor(rgb_camera_bp, transform, attach_to=vehicle, attachment_type=Attachment.Rigid)
|
||||
# Default attachment: Attachment.Rigid
|
||||
gnss_sensor = world.spawn_actor(sensor_gnss_bp, transform, attach_to=vehicle)
|
||||
collision_sensor = world.spawn_actor(sensor_collision_bp, transform, attach_to=vehicle)
|
||||
lane_invasion_sensor = world.spawn_actor(sensor_lane_invasion_bp, transform, attach_to=vehicle)
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.spawn_actor-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.World.get_spectator-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.get_spectator
|
||||
</p>
|
||||
<div id="carla.World.get_spectator-code" class="SnipetContent">
|
||||
|
||||
```py
|
||||
|
||||
|
||||
# This recipe spawns an actor and the spectator camera at the actor's location.
|
||||
|
||||
# ...
|
||||
world = client.get_world()
|
||||
spectator = world.get_spectator()
|
||||
|
||||
vehicle_bp = random.choice(world.get_blueprint_library().filter('vehicle.bmw.*'))
|
||||
transform = random.choice(world.get_map().get_spawn_points())
|
||||
vehicle = world.try_spawn_actor(vehicle_bp, transform)
|
||||
|
||||
# Wait for world to get the vehicle actor
|
||||
world.tick()
|
||||
|
||||
world_snapshot = world.wait_for_tick()
|
||||
actor_snapshot = world_snapshot.find(vehicle.id)
|
||||
|
||||
# Set spectator at given transform (vehicle transform)
|
||||
spectator.set_transform(actor_snapshot.get_transform())
|
||||
# ...
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.World.get_spectator-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
|
||||
</div>
|
||||
|
||||
|
|
|
@ -0,0 +1,75 @@
|
|||
# Chrono Integration
|
||||
|
||||
This guide outlines what Chrono is, how to use it in CARLA, and the limitations involved in the integration.
|
||||
|
||||
- [__Project Chrono__](#project-chrono)
|
||||
- [__Using Chrono on CARLA__](#using-chrono-on-carla)
|
||||
- [Configuring the server](#configuring-the-server)
|
||||
- [Enabling Chrono physics](#enabling-chrono-physics)
|
||||
- [__Limitations__](#limitations)
|
||||
|
||||
---
|
||||
|
||||
## Project Chrono
|
||||
|
||||
[Project Chrono](https://projectchrono.org/) is an open-source, multi-physics simulation engine that provides highly realistic vehicle dynamics using a template-based approach. The integration in CARLA allows users to utilize Chrono templates to simulate vehicle dynamics while navigating a map.
|
||||
|
||||
---
|
||||
|
||||
## Using Chrono on CARLA
|
||||
|
||||
To use the Chrono integration, you must first configure the server with a tag on startup and then use the PythonAPI to enable it on a spawned vehicle. Read on for more details.
|
||||
|
||||
### Configuring the server
|
||||
|
||||
Chrono will only work if the CARLA server is compiled with the Chrono tag.
|
||||
|
||||
__In the build from source version of CARLA__, run the following command to start the server:
|
||||
|
||||
```sh
|
||||
make launch ARGS="--chrono"
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
### Enabling Chrono physics
|
||||
|
||||
Chrono physics is enabled using the `enable_chrono_physics` method available through the [Actor](python_api.md#carlaactor) class. As well as values for substeps and substep delta time, it requires three template files and a base path to locate those files:
|
||||
|
||||
- __`base_path`:__ Path of the directory which contains the template files. This is necessary to ensure that auxiliary files referenced from the template files have a common base path from which to search.
|
||||
- __`vehicle_json`:__ Path of the vehicle template file relative to the `base_path`.
|
||||
- __`tire_json`:__ Path of the tire template file relative to the `base_path`.
|
||||
- __`powertrain_json`:__ Path of the powertrain template file relative to the `base_path`.
|
||||
|
||||
!!! Important
|
||||
Double-check your paths. Incorrect or missing paths can cause Unreal Engine to crash.
|
||||
|
||||
There are a variety of example template files for different vehicles available in `Build/chrono-install/share/chrono/data/vehicle`. Read the Project Chrono [documentation](https://api.projectchrono.org/manual_vehicle.html) to find out more about their vehicle examples and how to create templates.
|
||||
|
||||
See below for an example of how to enable Chrono physics:
|
||||
|
||||
```python
|
||||
# Spawn your vehicle
|
||||
vehicle = world.spawn_actor(bp, spawn_point)
|
||||
|
||||
# Set the base path
|
||||
base_path = "/path/to/carla/Build/chrono-install/share/chrono/data/vehicle/"
|
||||
|
||||
# Set the template files
|
||||
|
||||
vehicle_json = "sedan/vehicle/Sedan_Vehicle.json"
|
||||
powertrain_json = "sedan/powertrain/Sedan_SimpleMapPowertrain.json"
|
||||
tire_json = "sedan/tire/Sedan_TMeasyTire.json"
|
||||
|
||||
# Enable Chrono physics
|
||||
|
||||
vehicle.enable_chrono_physics(5000, 0.002, vehicle_json, powertrain_json, tire_json, base_path)
|
||||
```
|
||||
|
||||
You can try the Chrono physics integration using the example script `manual_control_chrono.py` found in `PythonAPI/examples`. After running the script, press `Ctrl + o` to enable Chrono.
|
||||
|
||||
---
|
||||
|
||||
### Limitations
|
||||
|
||||
This integration does not support collisions. __When a collision occurs, the vehicle will revert to CARLA default physics.__
|
|
@ -86,6 +86,39 @@
|
|||
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
|
||||
|
@ -95,7 +128,7 @@
|
|||
param_units: m/s
|
||||
doc: >
|
||||
Sets a vehicle's velocity vector to a constant value over time. The resulting velocity will be approximately the `velocity` being set, as with __<font color="#7fb800">set_target_velocity()</font>__.
|
||||
Note: >
|
||||
note: >
|
||||
Only carla.Vehicle actors can use this method.
|
||||
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.
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -54,6 +54,7 @@ nav:
|
|||
- 'CarSim Integration (Beta)': "tuto_G_carsim_integration.md"
|
||||
- 'RLlib Integration': "tuto_G_rllib_integration.md"
|
||||
- 'Scenic': 'tuto_G_scenic.md'
|
||||
- 'Chrono Integration': 'tuto_G_chrono.md'
|
||||
- Tutorials (assets):
|
||||
- 'Add a new map': 'tuto_A_add_map_overview.md'
|
||||
- 'Add a new vehicle': 'tuto_A_add_vehicle.md'
|
||||
|
|
Loading…
Reference in New Issue