Skip to content

Commit 8a2a7e9

Browse files
abanueloArmando BañuelosUbuntuArmando BanuelosArmando Banuelos
authored
feat: adding webots dynamic scenario tests (#231)
* feat: adding webots dynamic simulation, tbd tested * feat: Adding functional webots tests * fix: reformatting with black and isort and deleting unnecessary files * fix: improving code coverage * fix: black formatting test_webots.py * Adding codecov yml updates from main branch * fix: also including tests directory to ignore for coverage, not relevant * fix: adding checks for environment variables * fix: adjusting fixture call * fix: adding webots extension * fix: adding batch option to avoid popups * Add timeout to Webots dynamic test --------- Co-authored-by: Armando Bañuelos <[email protected]> Co-authored-by: Ubuntu <[email protected]> Co-authored-by: Armando Banuelos <[email protected]> Co-authored-by: Armando Banuelos <[email protected]> Co-authored-by: Lola Marrero <[email protected]>
1 parent ca74ae9 commit 8a2a7e9

File tree

7 files changed

+207
-0
lines changed

7 files changed

+207
-0
lines changed

tests/conftest.py

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,17 @@ def loader(relpath, **kwargs):
5151
return loader
5252

5353

54+
@pytest.fixture
55+
def launchWebots():
56+
DISPLAY = os.environ.get("DISPLAY")
57+
if not DISPLAY:
58+
pytest.skip("DISPLAY env variable not set.")
59+
WEBOTS_ROOT = os.environ.get("WEBOTS_ROOT")
60+
if not WEBOTS_ROOT:
61+
pytest.skip("WEBOTS_ROOT env variable not set.")
62+
return WEBOTS_ROOT
63+
64+
5465
## Command-line options
5566

5667

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
"""
2+
Create a Webots cube in air and have it drop
3+
"""
4+
5+
model scenic.simulators.webots.model
6+
7+
class Floor(Object):
8+
width: 5
9+
length: 5
10+
height: 0.01
11+
position: (0,0,0)
12+
color: [0.785, 0.785, 0.785]
13+
14+
class Block(WebotsObject):
15+
webotsAdhoc: {'physics': True}
16+
shape: BoxShape()
17+
width: 0.2
18+
length: 0.2
19+
height: 0.2
20+
density: 100
21+
color: [1, 0.502, 0]
22+
23+
floor = new Floor
24+
ego = new Block at (0, 0, 0.5) #above floor by 0.5
25+
26+
terminate when ego.z < 0.1
27+
record (ego.z) as BlockPosition
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
import os
2+
3+
from controller import Supervisor
4+
5+
import scenic
6+
from scenic.simulators.webots import WebotsSimulator
7+
8+
WEBOTS_RESULT_FILE_PATH = f"{os.path.dirname(__file__)}/../../../results.txt"
9+
10+
11+
def send_results(data):
12+
with open(WEBOTS_RESULT_FILE_PATH, "w") as file:
13+
file.write(data)
14+
15+
16+
supervisor = Supervisor()
17+
simulator = WebotsSimulator(supervisor)
18+
19+
path = supervisor.getCustomData()
20+
print(f"Loading Scenic scenario {path}")
21+
scenario = scenic.scenarioFromFile(path)
22+
23+
scene, _ = scenario.generate()
24+
simulation = simulator.simulate(scene, verbosity=2)
25+
block_movements = simulation.result.records["BlockPosition"]
26+
first_block_movement = block_movements[0]
27+
last_block_movement = block_movements[-1]
28+
blocks = [first_block_movement, last_block_movement]
29+
supervisor.simulationQuit(status="finished")
30+
send_results(str(blocks))
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
#VRML_SIM R2023a utf8
2+
3+
PROTO ScenicObject [
4+
field SFVec3f translation 0 0 0
5+
field SFRotation rotation 0 0 1 0
6+
field SFString name "solid"
7+
field SFVec3f angularVelocity 0 0 0
8+
field MFString url ""
9+
]
10+
{
11+
Solid {
12+
translation IS translation
13+
rotation IS rotation
14+
name IS name
15+
angularVelocity IS angularVelocity
16+
children [
17+
CadShape {
18+
url IS url
19+
castShadows FALSE
20+
}
21+
]
22+
boundingObject Shape {
23+
geometry Mesh {
24+
url IS url
25+
}
26+
}
27+
}
28+
}
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
#VRML_SIM R2023a utf8
2+
3+
PROTO ScenicObjectWithPhysics [
4+
field SFVec3f translation 0 0 0
5+
field SFRotation rotation 0 0 1 0
6+
field SFString name "solid"
7+
field SFVec3f angularVelocity 0 0 0
8+
field MFString url ""
9+
field SFFloat density 1000 # kg / m^3
10+
]
11+
{
12+
Solid {
13+
translation IS translation
14+
rotation IS rotation
15+
name IS name
16+
angularVelocity IS angularVelocity
17+
children [
18+
CadShape {
19+
url IS url
20+
castShadows FALSE
21+
}
22+
]
23+
boundingObject Shape {
24+
geometry Mesh {
25+
url IS url
26+
}
27+
}
28+
physics Physics {
29+
# density will be set by the simulator
30+
density IS density
31+
mass -1
32+
}
33+
}
34+
}
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
#VRML_SIM R2023a utf8
2+
3+
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto"
4+
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto"
5+
IMPORTABLE EXTERNPROTO "../protos/ScenicObject.proto"
6+
IMPORTABLE EXTERNPROTO "../protos/ScenicObjectWithPhysics.proto"
7+
8+
WorldInfo {
9+
gravity 3
10+
basicTimeStep 16
11+
contactProperties [
12+
ContactProperties {
13+
coulombFriction [
14+
0.8
15+
]
16+
}
17+
]
18+
}
19+
Viewpoint {
20+
orientation -0.19729161510865992 0.07408415124219735 0.977541588446517 2.4380019050245862
21+
position 6.683615307234937 -5.5006366813466805 4.16419445995153
22+
}
23+
TexturedBackground {
24+
}
25+
Floor {
26+
name "FLOOR"
27+
size 5 5
28+
}
29+
Robot {
30+
name "Supervisor"
31+
controller "scenic_supervisor"
32+
customData "../../../dynamic.scenic"
33+
supervisor TRUE
34+
}

tests/simulators/webots/test_webots.py

Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,50 @@
1+
import os
2+
import subprocess
3+
14
import pytest
25

36
from tests.utils import pickle_test, sampleScene, tryPickling
47

8+
WEBOTS_RESULTS_FILE_PATH = f"{os.path.dirname(__file__)}/dynamic/results.txt"
9+
WEBOTS_WORLD_FILE_PATH = (
10+
f"{os.path.dirname(__file__)}/dynamic/webots_data/worlds/world.wbt"
11+
)
12+
13+
14+
def receive_results():
15+
with open(WEBOTS_RESULTS_FILE_PATH, "r") as file:
16+
content = file.read()
17+
return content
18+
19+
20+
def cleanup_results():
21+
command = f"rm -f {WEBOTS_RESULTS_FILE_PATH}"
22+
subprocess.run(command, shell=True)
23+
24+
25+
def test_dynamics_scenarios(launchWebots):
26+
WEBOTS_ROOT = launchWebots
27+
cleanup_results()
28+
29+
timeout_seconds = 300
30+
31+
command = f"bash {WEBOTS_ROOT}/webots --no-rendering --minimize --batch {WEBOTS_WORLD_FILE_PATH}"
32+
33+
try:
34+
subprocess.run(command, shell=True, timeout=timeout_seconds)
35+
except subprocess.TimeoutExpired:
36+
pytest.fail(f"Webots test exceeded the timeout of {timeout_seconds} seconds and failed.")
37+
38+
data = receive_results()
39+
assert data != None
40+
start_z = float(data.split(",")[1].strip(" )]"))
41+
end_z = float(data.split(",")[3].strip(" )]"))
42+
assert start_z == 0.5
43+
assert start_z > end_z
44+
expected_value = 0.09
45+
tolerance = 0.01
46+
assert end_z == pytest.approx(expected_value, abs=tolerance)
47+
548

649
def test_basic(loadLocalScenario):
750
scenario = loadLocalScenario("basic.scenic")

0 commit comments

Comments
 (0)