Skip to content

Commit 1df5d88

Browse files
committed
Fix tests
1 parent d08cea6 commit 1df5d88

File tree

4 files changed

+16
-11
lines changed

4 files changed

+16
-11
lines changed

smarts/bullet/bullet_simulation.py

+5-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
# THE SOFTWARE.
2222
import importlib.resources as pkg_resources
2323
import os
24-
from typing import Any
24+
from typing import Any, Optional
2525

2626
from smarts.bullet import pybullet
2727
from smarts.bullet.pybullet import bullet_client as bc
@@ -124,7 +124,10 @@ def initialize_ground(self, resource_path, map_bb):
124124
)
125125

126126
def step(
127-
self, dt: float, simulation_frame: SimulationFrame, vehicle_index: VehicleIndex
127+
self,
128+
dt: float,
129+
simulation_frame: Optional[SimulationFrame],
130+
vehicle_index: VehicleIndex,
128131
):
129132
self._bullet_client.stepSimulation()
130133
pybullet_substeps = max(1, round(dt / self._pybullet_period)) - 1

smarts/core/physics/physics_simulation.py

+5-2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
2020
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
2121
# THE SOFTWARE.
22-
from typing import Any
22+
from typing import Any, Optional
2323

2424
from smarts.core.coordinates import BoundingBox
2525
from smarts.core.simulation_frame import SimulationFrame
@@ -56,7 +56,10 @@ def teardown(self):
5656
raise NotImplementedError
5757

5858
def step(
59-
self, dt: float, simulation_frame: SimulationFrame, vehicle_index: VehicleIndex
59+
self,
60+
dt: float,
61+
simulation_frame: Optional[SimulationFrame],
62+
vehicle_index: VehicleIndex,
6063
):
6164
"""Step the current physics simulation.
6265

smarts/core/tests/test_collision.py

+5-4
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
from smarts.core.smarts import SMARTS
3838
from smarts.core.sumo_traffic_simulation import SumoTrafficSimulation
3939
from smarts.core.vehicle import VEHICLE_CONFIGS
40+
from smarts.core.vehicle_index import VehicleIndex
4041
from smarts.sstudio import gen_scenario
4142
from smarts.sstudio import types as t
4243

@@ -63,7 +64,7 @@ def step_with_vehicle_commands(
6364
collisions = []
6465
for _ in range(steps):
6566
bv.control(throttle, brake, steering)
66-
bullet_simulation.step()
67+
bullet_simulation.step(time_step, None, vehicle_index=VehicleIndex.identity())
6768
collisions.extend(bv.contact_points)
6869
return collisions
6970

@@ -80,7 +81,7 @@ def step_with_pose_delta(
8081
cur_pose = bv.pose
8182
new_pose = Pose.from_center(cur_pose.position + pose_delta, cur_pose.heading)
8283
bv.control(new_pose, speed)
83-
bullet_simulation.step()
84+
bullet_simulation.step(time_step, None, VehicleIndex.identity())
8485
collisions.extend(bv.contact_points)
8586
return collisions
8687

@@ -99,7 +100,7 @@ def test_collision(bullet_simulation: BulletSimulation):
99100
bullet_client=bullet_simulation.client,
100101
)
101102

102-
collisions = step_with_vehicle_commands(chassis, steps=2)
103+
collisions = step_with_vehicle_commands(chassis, bullet_simulation, steps=2)
103104
assert len(collisions) > 0
104105
collided_bullet_ids = set([c.bullet_id for c in collisions])
105106
GROUND_ID = 0
@@ -199,7 +200,7 @@ def _joust(
199200
for _ in range(steps):
200201
wkc.control(throttle)
201202
bkc.control(throttle)
202-
bullet_simulation.step()
203+
bullet_simulation.step(time_step, None, VehicleIndex.identity())
203204
collisions[0].extend(wkc.contact_points)
204205
collisions[1].extend(bkc.contact_points)
205206
return collisions

smarts/core/tests/test_trajectory_controller.py

+1-3
Original file line numberDiff line numberDiff line change
@@ -162,7 +162,5 @@ def step_with_vehicle_commands(
162162
def test_trajectory_tracking(
163163
bullet_simulation: BulletSimulation, vehicle, radius, omega
164164
):
165-
final_error = step_with_vehicle_commands(
166-
bullet_simulation.client, vehicle, radius, omega
167-
)
165+
final_error = step_with_vehicle_commands(bullet_simulation, vehicle, radius, omega)
168166
assert final_error <= 10

0 commit comments

Comments
 (0)