Skip to content

Commit 97815cd

Browse files
committed
added max_real_delta_seconds parameter to limit sim speed
1 parent 20019a1 commit 97815cd

File tree

5 files changed

+12
-0
lines changed

5 files changed

+12
-0
lines changed

simulator/carla_autoware/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,7 @@ All the key parameters can be configured in `carla_autoware.launch.xml`.
7373
| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) |
7474
| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA |
7575
| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA |
76+
| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` |
7677

7778
### Configurable Parameters for Sensors
7879

simulator/carla_autoware/launch/carla_autoware.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
<arg name="fixed_delta_seconds" default="0.05" description="Timestep for CARLA, FPS=1/value"/>
1111
<arg name="objects_definition_file" default="$(find-pkg-share carla_autoware)/objects.json"/>
1212
<arg name="use_traffic_manager" default="False"/>
13+
<arg name="max_real_delta_seconds" default="0.05"/>
1314

1415
<!-- CARLA Interface -->
1516
<node pkg="carla_autoware" exec="carla_autoware" name="carla_autoware" output="screen">
@@ -24,6 +25,7 @@
2425
<param name="vehicle_type" value="$(var vehicle_type)"/>
2526
<param name="objects_definition_file" value="$(var objects_definition_file)"/>
2627
<param name="use_traffic_manager" value="$(var use_traffic_manager)"/>
28+
<param name="max_real_delta_seconds" value="$(var max_real_delta_seconds)"/>
2729
</node>
2830

2931
<!-- Awsim configuration frame to CARLA frame -->

simulator/carla_autoware/resource/carla_autoware

Whitespace-only changes.

simulator/carla_autoware/src/carla_autoware/carla_autoware.py

+8
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ def __init__(self):
6060
self.world = None
6161
self.sensor_wrapper = None
6262
self.ego_vehicle = None
63+
self.timestamp_last_run = 0.0
64+
self.delta_step = 0.0
6365

6466
# Parameter for Initializing Carla World
6567
self.local_host = self.param_["host"]
@@ -72,6 +74,7 @@ def __init__(self):
7274
self.vehicle_type = self.param_["vehicle_type"]
7375
self.spawn_point = self.param_["spawn_point"]
7476
self.use_traffic_manager = self.param_["use_traffic_manager"]
77+
self.max_real_delta_seconds = self.param_["max_real_delta_seconds"]
7578

7679
def load_world(self):
7780
client = carla.Client(self.local_host, self.port)
@@ -164,6 +167,11 @@ def run_bridge(self):
164167
if snapshot:
165168
timestamp = snapshot.timestamp
166169
if timestamp:
170+
self.delta_step = timestamp.elapsed_seconds - self.timestamp_last_run
171+
if self.delta_step < self.max_real_delta_seconds:
172+
# Add a wait to match the max_real_delta_seconds
173+
time.sleep(self.max_real_delta_seconds - self.delta_step)
174+
self.timestamp_last_run = timestamp.elapsed_seconds
167175
self.bridge_loop._tick_sensor(timestamp)
168176

169177
def _stop_loop(self, signum, frame):

simulator/carla_autoware/src/carla_autoware/carla_ros.py

+1
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,7 @@ def setup(self):
9494
"vehicle_type": rclpy.Parameter.Type.STRING,
9595
"objects_definition_file": rclpy.Parameter.Type.STRING,
9696
"use_traffic_manager": rclpy.Parameter.Type.BOOL,
97+
"max_real_delta_seconds": rclpy.Parameter.Type.DOUBLE,
9798
}
9899
self.param_values = {}
99100
for param_name, param_type in self.parameters.items():

0 commit comments

Comments
 (0)