"""
Unit tests for world generation tools.
Tests Phase 4 functionality:
- Obstacle course generation
- Material properties listing
- Lighting presets
- Day/night cycle calculations
"""
import pytest
from unittest.mock import patch, Mock
import sys
from pathlib import Path
# Add src to path:
PROJECT_ROOT = Path(__file__).parent.parent.parent
sys.path.insert(0, str(PROJECT_ROOT / "src"))
from gazebo_mcp.tools import world_generation
from gazebo_mcp.utils import OperationResult
class TestCreateObstacleCourse:
"""Test obstacle course generation."""
def test_default_parameters(self):
"""Test obstacle course with default parameters."""
result = world_generation.create_obstacle_course()
assert result.success is True
assert "obstacles" in result.data
assert "area_size" in result.data
assert "num_obstacles" in result.data
obstacles = result.data["obstacles"]
assert len(obstacles) == 10 # Default num_obstacles
assert result.data["area_size"] == 20.0
assert result.data["num_obstacles"] == 10
def test_custom_num_obstacles(self):
"""Test with custom number of obstacles."""
result = world_generation.create_obstacle_course(num_obstacles=5)
assert result.success is True
assert len(result.data["obstacles"]) == 5
assert result.data["num_obstacles"] == 5
def test_custom_area_size(self):
"""Test with custom area size."""
result = world_generation.create_obstacle_course(area_size=30.0)
assert result.success is True
assert result.data["area_size"] == 30.0
# Check obstacles are within area bounds
for obs in result.data["obstacles"]:
assert -15.0 <= obs["position"]["x"] <= 15.0 # area_size / 2
assert -15.0 <= obs["position"]["y"] <= 15.0
def test_custom_obstacle_types(self):
"""Test with custom obstacle types."""
custom_types = ["box", "cylinder"]
result = world_generation.create_obstacle_course(
num_obstacles=5, obstacle_types=custom_types
)
assert result.success is True
for obs in result.data["obstacles"]:
assert obs["type"] in custom_types
def test_min_distance_enforcement(self):
"""Test that obstacles respect minimum distance."""
result = world_generation.create_obstacle_course(num_obstacles=5, min_distance=3.0, seed=42)
assert result.success is True
obstacles = result.data["obstacles"]
# Check all pairs have min distance
for i, obs1 in enumerate(obstacles):
for obs2 in obstacles[i + 1 :]:
dx = obs1["position"]["x"] - obs2["position"]["x"]
dy = obs1["position"]["y"] - obs2["position"]["y"]
distance = (dx * dx + dy * dy) ** 0.5
assert distance >= 3.0
def test_seed_reproducibility(self):
"""Test that same seed produces same layout."""
result1 = world_generation.create_obstacle_course(num_obstacles=5, seed=42)
result2 = world_generation.create_obstacle_course(num_obstacles=5, seed=42)
assert result1.success is True
assert result2.success is True
# Should be identical
for obs1, obs2 in zip(result1.data["obstacles"], result2.data["obstacles"]):
assert obs1["position"]["x"] == obs2["position"]["x"]
assert obs1["position"]["y"] == obs2["position"]["y"]
assert obs1["type"] == obs2["type"]
def test_different_seeds_different_layouts(self):
"""Test that different seeds produce different layouts."""
result1 = world_generation.create_obstacle_course(num_obstacles=5, seed=42)
result2 = world_generation.create_obstacle_course(num_obstacles=5, seed=99)
assert result1.success is True
assert result2.success is True
# Should be different (at least one position differs)
different = False
for obs1, obs2 in zip(result1.data["obstacles"], result2.data["obstacles"]):
if (
obs1["position"]["x"] != obs2["position"]["x"]
or obs1["position"]["y"] != obs2["position"]["y"]
):
different = True
break
assert different is True
def test_obstacle_structure(self):
"""Test that obstacles have correct structure."""
result = world_generation.create_obstacle_course(num_obstacles=3)
assert result.success is True
for obs in result.data["obstacles"]:
# Required fields
assert "type" in obs
assert "position" in obs
assert "size" in obs
assert "color" in obs
# Position structure
assert "x" in obs["position"]
assert "y" in obs["position"]
assert "z" in obs["position"]
# Size is a float
assert isinstance(obs["size"], (int, float))
assert obs["size"] > 0.0
# Color structure
assert "r" in obs["color"]
assert "g" in obs["color"]
assert "b" in obs["color"]
assert "a" in obs["color"]
def test_invalid_num_obstacles(self):
"""Test validation for invalid num_obstacles."""
result = world_generation.create_obstacle_course(num_obstacles=0)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
result = world_generation.create_obstacle_course(num_obstacles=-5)
assert result.success is False
def test_invalid_area_size(self):
"""Test validation for invalid area_size."""
result = world_generation.create_obstacle_course(area_size=0.0)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
result = world_generation.create_obstacle_course(area_size=-10.0)
assert result.success is False
def test_invalid_min_distance(self):
"""Test validation for invalid min_distance."""
result = world_generation.create_obstacle_course(min_distance=-1.0)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
def test_impossible_placement(self):
"""Test when obstacles can't fit with min_distance."""
# 100 obstacles in 10x10 area with 5m spacing = impossible
result = world_generation.create_obstacle_course(
num_obstacles=100, area_size=10.0, min_distance=5.0
)
# Should fail gracefully
assert result.success is False
assert result.error_code == "GENERATION_ERROR"
assert result.suggestions is not None
assert len(result.suggestions) > 0
class TestListMaterials:
"""Test material properties listing."""
def test_list_materials_success(self):
"""Test listing all materials."""
result = world_generation.list_materials()
assert result.success is True
assert "materials" in result.data
assert "count" in result.data
materials = result.data["materials"]
assert len(materials) > 0
assert result.data["count"] == len(materials)
def test_material_structure(self):
"""Test that each material has correct structure."""
result = world_generation.list_materials()
assert result.success is True
for name, props in result.data["materials"].items():
# Required properties
assert "friction" in props
assert "restitution" in props
assert "color" in props
assert "description" in props
# Friction range
assert 0.0 <= props["friction"] <= 10.0
# Restitution range (bounciness)
assert 0.0 <= props["restitution"] <= 1.0
# Color structure
color = props["color"]
assert "r" in color
assert "g" in color
assert "b" in color
assert "a" in color
assert 0.0 <= color["r"] <= 1.0
assert 0.0 <= color["g"] <= 1.0
assert 0.0 <= color["b"] <= 1.0
assert 0.0 <= color["a"] <= 1.0
def test_expected_materials(self):
"""Test that expected materials are present."""
result = world_generation.list_materials()
assert result.success is True
materials = result.data["materials"]
# Should have these materials
expected = ["grass", "concrete", "ice", "sand", "wood", "rubber"]
for material in expected:
assert material in materials
def test_ice_has_low_friction(self):
"""Test that ice has appropriately low friction."""
result = world_generation.list_materials()
assert result.success is True
ice = result.data["materials"]["ice"]
assert ice["friction"] < 0.2 # Very slippery
def test_rubber_has_high_restitution(self):
"""Test that rubber has high restitution (bouncy)."""
result = world_generation.list_materials()
assert result.success is True
rubber = result.data["materials"]["rubber"]
assert rubber["restitution"] > 0.7 # Very bouncy
class TestCreateLightingPreset:
"""Test lighting preset creation."""
def test_day_preset(self):
"""Test day lighting preset."""
result = world_generation.create_lighting_preset("day")
assert result.success is True
assert result.data["preset"] == "day"
assert "lighting" in result.data
lighting = result.data["lighting"]
assert "ambient" in lighting
assert "sun_angle" in lighting
assert "sun_color" in lighting
assert "shadows" in lighting
# Day should be bright
ambient = lighting["ambient"]
assert ambient["r"] > 0.5
assert ambient["g"] > 0.5
assert ambient["b"] > 0.5
def test_night_preset(self):
"""Test night lighting preset."""
result = world_generation.create_lighting_preset("night")
assert result.success is True
assert result.data["preset"] == "night"
# Night should be dark
lighting = result.data["lighting"]
ambient = lighting["ambient"]
assert ambient["r"] < 0.3
assert ambient["g"] < 0.3
assert ambient["b"] < 0.3
def test_dawn_preset(self):
"""Test dawn lighting preset."""
result = world_generation.create_lighting_preset("dawn")
assert result.success is True
assert result.data["preset"] == "dawn"
# Dawn should have orange/red tones
lighting = result.data["lighting"]
sun_color = lighting["sun_color"]
assert sun_color["r"] > sun_color["b"] # More red than blue
def test_dusk_preset(self):
"""Test dusk lighting preset."""
result = world_generation.create_lighting_preset("dusk")
assert result.success is True
assert result.data["preset"] == "dusk"
def test_indoor_preset(self):
"""Test indoor lighting preset."""
result = world_generation.create_lighting_preset("indoor")
assert result.success is True
assert result.data["preset"] == "indoor"
def test_warehouse_preset(self):
"""Test warehouse lighting preset."""
result = world_generation.create_lighting_preset("warehouse")
assert result.success is True
assert result.data["preset"] == "warehouse"
def test_intensity_scaling(self):
"""Test that intensity parameter scales lighting."""
result1 = world_generation.create_lighting_preset("day", intensity=1.0)
result2 = world_generation.create_lighting_preset("day", intensity=0.5)
assert result1.success is True
assert result2.success is True
# Half intensity should be darker
lighting1 = result1.data["lighting"]
lighting2 = result2.data["lighting"]
assert lighting2["ambient"]["r"] < lighting1["ambient"]["r"]
assert lighting2["ambient"]["g"] < lighting1["ambient"]["g"]
assert lighting2["ambient"]["b"] < lighting1["ambient"]["b"]
def test_invalid_preset_name(self):
"""Test validation for invalid preset name."""
result = world_generation.create_lighting_preset("invalid_preset")
assert result.success is False
assert result.error_code == "INVALID_PARAMETER"
assert result.suggestions is not None
assert len(result.suggestions) > 0
def test_invalid_intensity(self):
"""Test validation for invalid intensity."""
result = world_generation.create_lighting_preset("day", intensity=-1.0)
assert result.success is False
result = world_generation.create_lighting_preset("day", intensity=0.0)
assert result.success is False
def test_color_structure(self):
"""Test that colors have correct structure."""
result = world_generation.create_lighting_preset("day")
assert result.success is True
lighting = result.data["lighting"]
# Check ambient color
ambient = lighting["ambient"]
assert "r" in ambient
assert "g" in ambient
assert "b" in ambient
assert "a" in ambient
# Check sun color
sun_color = lighting["sun_color"]
assert "r" in sun_color
assert "g" in sun_color
assert "b" in sun_color
assert "a" in sun_color
class TestCalculateDayNightCycle:
"""Test day/night cycle calculations."""
def test_noon_calculation(self):
"""Test calculation at noon (12:00)."""
result = world_generation.calculate_day_night_cycle(12.0)
assert result.success is True
assert result.data["time_of_day"] == 12.0
assert result.data["phase"] == "day"
# Sun should be high at noon
assert result.data["sun_angle"] > 60.0
def test_midnight_calculation(self):
"""Test calculation at midnight (0:00)."""
result = world_generation.calculate_day_night_cycle(0.0)
assert result.success is True
assert result.data["phase"] == "night"
# Sun should be below horizon at midnight
assert result.data["sun_angle"] < 0.0
def test_dawn_calculation(self):
"""Test calculation at dawn (6:00)."""
result = world_generation.calculate_day_night_cycle(6.0)
assert result.success is True
assert result.data["phase"] in ["dawn", "day"]
# Sun should be low at dawn
assert -10.0 <= result.data["sun_angle"] <= 30.0
def test_dusk_calculation(self):
"""Test calculation at dusk (18:00)."""
result = world_generation.calculate_day_night_cycle(18.0)
assert result.success is True
assert result.data["phase"] in ["dusk", "night"]
# Sun should be low at dusk
assert -10.0 <= result.data["sun_angle"] <= 30.0
def test_color_structure(self):
"""Test that colors have correct structure."""
result = world_generation.calculate_day_night_cycle(12.0)
assert result.success is True
# Check ambient color
assert "ambient" in result.data
ambient = result.data["ambient"]
assert "r" in ambient
assert "g" in ambient
assert "b" in ambient
assert "a" in ambient
# Check sun color
assert "sun_color" in result.data
sun = result.data["sun_color"]
assert "r" in sun
assert "g" in sun
assert "b" in sun
assert "a" in sun
def test_day_brighter_than_night(self):
"""Test that day is brighter than night."""
day_result = world_generation.calculate_day_night_cycle(12.0)
night_result = world_generation.calculate_day_night_cycle(0.0)
assert day_result.success is True
assert night_result.success is True
day_ambient = day_result.data["ambient"]
night_ambient = night_result.data["ambient"]
# Day should be brighter
assert day_ambient["r"] > night_ambient["r"]
assert day_ambient["g"] > night_ambient["g"]
assert day_ambient["b"] > night_ambient["b"]
def test_dawn_orange_tones(self):
"""Test that dawn has orange/red tones."""
result = world_generation.calculate_day_night_cycle(6.0)
assert result.success is True
sun_color = result.data["sun_color"]
# Should have more red than blue at dawn
assert sun_color["r"] >= sun_color["b"]
def test_custom_cycle_duration(self):
"""Test with custom cycle duration."""
result = world_generation.calculate_day_night_cycle(12.0, cycle_duration=48.0)
assert result.success is True
assert result.data["cycle_duration"] == 48.0
def test_invalid_time_of_day(self):
"""Test validation for invalid time of day."""
result = world_generation.calculate_day_night_cycle(-1.0)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
result = world_generation.calculate_day_night_cycle(25.0)
assert result.success is False
def test_invalid_cycle_duration(self):
"""Test validation for invalid cycle duration."""
# Note: Current implementation doesn't validate cycle_duration
# This test documents expected behavior for future improvement
result = world_generation.calculate_day_night_cycle(12.0, cycle_duration=0.0)
# Currently passes but should validate in future
assert result.success is True or result.success is False
result = world_generation.calculate_day_night_cycle(12.0, cycle_duration=-1.0)
# Currently passes but should validate in future
assert result.success is True or result.success is False
def test_full_day_coverage(self):
"""Test calculations across full 24-hour cycle."""
times = [0.0, 3.0, 6.0, 9.0, 12.0, 15.0, 18.0, 21.0]
for time in times:
result = world_generation.calculate_day_night_cycle(time)
assert result.success is True
assert result.data["time_of_day"] == time
assert result.data["phase"] in ["dawn", "day", "dusk", "night"]
def test_smooth_transitions(self):
"""Test that adjacent times produce smooth transitions."""
result1 = world_generation.calculate_day_night_cycle(11.9)
result2 = world_generation.calculate_day_night_cycle(12.0)
result3 = world_generation.calculate_day_night_cycle(12.1)
assert result1.success is True
assert result2.success is True
assert result3.success is True
# Sun angles should be close
angle1 = result1.data["sun_angle"]
angle2 = result2.data["sun_angle"]
angle3 = result3.data["sun_angle"]
assert abs(angle2 - angle1) < 5.0
assert abs(angle3 - angle2) < 5.0
class TestGenerateHeightmapTerrain:
"""Tests for generate_heightmap_terrain() function."""
def test_flat_pattern(self):
"""Test flat terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat", min_elevation=5.0, max_elevation=10.0
)
assert result.success is True
assert "elevation_data" in result.data
assert result.data["width"] == 129
assert result.data["height"] == 129
assert result.data["pattern"] == "flat"
# All elevations should be min_elevation for flat terrain
elevation_data = result.data["elevation_data"]
for row in elevation_data:
for elevation in row:
assert elevation == pytest.approx(5.0, abs=0.01)
def test_ramp_pattern(self):
"""Test ramp terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="ramp", min_elevation=0.0, max_elevation=10.0
)
assert result.success is True
elevation_data = result.data["elevation_data"]
# First row should be near min_elevation
assert elevation_data[0][64] < 1.0
# Last row should be near max_elevation
assert elevation_data[-1][64] > 9.0
def test_hills_pattern(self):
"""Test hills terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="hills", min_elevation=0.0, max_elevation=10.0
)
assert result.success is True
assert result.data["pattern"] == "hills"
# Hills should have variation
elevation_data = result.data["elevation_data"]
elevations = [elevation for row in elevation_data for elevation in row]
assert min(elevations) >= 0.0
assert max(elevations) <= 10.0
assert max(elevations) - min(elevations) > 1.0 # Has variation
def test_mountains_pattern(self):
"""Test mountains terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="mountains", min_elevation=0.0, max_elevation=20.0
)
assert result.success is True
assert result.data["pattern"] == "mountains"
# Should have peaks and valleys
elevation_data = result.data["elevation_data"]
elevations = [elevation for row in elevation_data for elevation in row]
assert max(elevations) - min(elevations) > 5.0
def test_random_pattern(self):
"""Test random terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="random", min_elevation=0.0, max_elevation=10.0
)
assert result.success is True
assert result.data["pattern"] == "random"
# Random terrain should have high variation
elevation_data = result.data["elevation_data"]
elevations = [elevation for row in elevation_data for elevation in row]
assert max(elevations) - min(elevations) > 2.0
def test_canyon_pattern(self):
"""Test canyon terrain generation."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="canyon", min_elevation=0.0, max_elevation=10.0
)
assert result.success is True
assert result.data["pattern"] == "canyon"
# Canyon should have flat center and high edges
elevation_data = result.data["elevation_data"]
# Center column should be near min_elevation
center_col = 64
center_elevations = [row[center_col] for row in elevation_data]
assert max(center_elevations) < 2.0
# Edge columns should be higher
edge_col = 10
edge_elevations = [row[edge_col] for row in elevation_data]
assert max(edge_elevations) > 5.0
def test_smoothness_parameter(self):
"""Test that smoothness parameter affects terrain."""
result1 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="hills", smoothness=1.0
)
result2 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="hills", smoothness=3.0
)
assert result1.success is True
assert result2.success is True
# Both should produce valid heightmaps
assert result1.data["smoothness"] == 1.0
assert result2.data["smoothness"] == 3.0
def test_seed_reproducibility(self):
"""Test that same seed produces same terrain."""
seed = 42
result1 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="random", seed=seed
)
result2 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="random", seed=seed
)
assert result1.success is True
assert result2.success is True
# Elevation data should be identical
assert result1.data["elevation_data"] == result2.data["elevation_data"]
def test_different_seeds_different_terrain(self):
"""Test that different seeds produce different terrain."""
result1 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="random", seed=42
)
result2 = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="random", seed=43
)
assert result1.success is True
assert result2.success is True
# Elevation data should be different
assert result1.data["elevation_data"] != result2.data["elevation_data"]
def test_invalid_pattern(self):
"""Test that invalid pattern returns error."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="invalid_pattern"
)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
assert "pattern" in result.error.lower()
def test_invalid_width_not_power_of_2_plus_1(self):
"""Test that invalid width (not 2^n + 1) returns error."""
result = world_generation.generate_heightmap_terrain(
width=100, height=129, pattern="flat"
)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
assert "width must be 2^n + 1" in result.error
def test_invalid_height_not_power_of_2_plus_1(self):
"""Test that invalid height (not 2^n + 1) returns error."""
result = world_generation.generate_heightmap_terrain(
width=129, height=100, pattern="flat"
)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
assert "height must be 2^n + 1" in result.error
def test_valid_dimensions(self):
"""Test that all valid dimensions work."""
valid_sizes = [3, 5, 9, 17, 33, 65, 129, 257, 513]
for size in valid_sizes[:3]: # Test first 3 for speed
result = world_generation.generate_heightmap_terrain(
width=size, height=size, pattern="flat"
)
assert result.success is True
assert result.data["width"] == size
assert result.data["height"] == size
def test_min_elevation_greater_than_max(self):
"""Test that min > max returns error."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat", min_elevation=10.0, max_elevation=5.0
)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
def test_statistics_calculation(self):
"""Test that statistics are calculated correctly."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat", min_elevation=5.0, max_elevation=10.0
)
assert result.success is True
assert "min_elevation" in result.data
assert "max_elevation" in result.data
assert "avg_elevation" in result.data
# Flat terrain should have all same elevation
assert result.data["min_elevation"] == pytest.approx(5.0, abs=0.01)
assert result.data["max_elevation"] == pytest.approx(5.0, abs=0.01)
assert result.data["avg_elevation"] == pytest.approx(5.0, abs=0.01)
def test_total_points(self):
"""Test that total_points is calculated correctly."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat"
)
assert result.success is True
assert result.data["total_points"] == 129 * 129
def test_example_sdf_included(self):
"""Test that example SDF is included in result."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat"
)
assert result.success is True
assert "example_sdf" in result.data
assert "<heightmap>" in result.data["example_sdf"]
assert "<size>129 129" in result.data["example_sdf"]
def test_timestamp_included(self):
"""Test that timestamp is included."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat"
)
assert result.success is True
assert "timestamp" in result.data
def test_note_included(self):
"""Test that helpful note is included."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="flat"
)
assert result.success is True
assert "note" in result.data
assert "heightmap" in result.data["note"].lower()
def test_small_dimensions(self):
"""Test smallest valid dimensions."""
result = world_generation.generate_heightmap_terrain(
width=3, height=3, pattern="flat"
)
assert result.success is True
assert len(result.data["elevation_data"]) == 3
assert len(result.data["elevation_data"][0]) == 3
def test_large_dimensions(self):
"""Test larger dimensions."""
result = world_generation.generate_heightmap_terrain(
width=257, height=257, pattern="flat"
)
assert result.success is True
assert len(result.data["elevation_data"]) == 257
assert len(result.data["elevation_data"][0]) == 257
def test_negative_smoothness(self):
"""Test that negative smoothness is rejected."""
result = world_generation.generate_heightmap_terrain(
width=129, height=129, pattern="hills", smoothness=-1.0
)
assert result.success is False
assert "INVALID_PARAMETER" in result.error_code
class TestCreateEmptyWorld:
"""Test empty world creation."""
def test_default_parameters(self):
"""Test creating world with default parameters."""
result = world_generation.create_empty_world("test_world")
assert result.success is True
assert "world_name" in result.data
assert "sdf_content" in result.data
assert result.data["world_name"] == "test_world"
assert "<world name=\"test_world\">" in result.data["sdf_content"]
assert "<physics" in result.data["sdf_content"]
def test_with_ground_plane(self):
"""Test world with ground plane."""
result = world_generation.create_empty_world(
"test_world", include_ground_plane=True
)
assert result.success is True
assert "<model name=\"ground_plane\">" in result.data["sdf_content"]
assert "<plane>" in result.data["sdf_content"]
def test_without_ground_plane(self):
"""Test world without ground plane."""
result = world_generation.create_empty_world(
"test_world", include_ground_plane=False
)
assert result.success is True
assert "ground_plane" not in result.data["sdf_content"]
def test_with_sun(self):
"""Test world with sun lighting."""
result = world_generation.create_empty_world("test_world", include_sun=True)
assert result.success is True
assert "<light" in result.data["sdf_content"]
assert "type=\"directional\"" in result.data["sdf_content"]
def test_without_sun(self):
"""Test world without sun lighting."""
result = world_generation.create_empty_world("test_world", include_sun=False)
assert result.success is True
# Should not have directional light
directional_count = result.data["sdf_content"].count('type="directional"')
assert directional_count == 0
def test_valid_sdf_structure(self):
"""Test that generated SDF has valid structure."""
result = world_generation.create_empty_world("test_world")
assert result.success is True
sdf = result.data["sdf_content"]
# Check required elements
assert sdf.startswith('<?xml version="1.0"')
assert '<sdf version="1.7">' in sdf or '<sdf version="1.8">' in sdf
assert "</sdf>" in sdf
assert "<world" in sdf
assert "</world>" in sdf
def test_physics_configuration(self):
"""Test that physics is configured."""
result = world_generation.create_empty_world("test_world")
assert result.success is True
assert "<physics" in result.data["sdf_content"]
assert "<max_step_size>" in result.data["sdf_content"]
assert "<real_time_factor>" in result.data["sdf_content"]
def test_invalid_world_name(self):
"""Test that invalid world name returns error."""
result = world_generation.create_empty_world("")
assert result.success is False
assert ("INVALID_PARAMETER" in result.error_code or
"MISSING_PARAMETER" in result.error_code)
def test_scene_configuration(self):
"""Test that scene is configured."""
result = world_generation.create_empty_world("test_world")
assert result.success is True
assert "<scene>" in result.data["sdf_content"]
assert "<ambient>" in result.data["sdf_content"]
class TestSaveWorld:
"""Test saving world files."""
def test_save_world_success(self, tmp_path):
"""Test saving world to file."""
world_content = '<?xml version="1.0"?><sdf version="1.7"><world name="test"></world></sdf>'
file_path = tmp_path / "test_world.sdf"
result = world_generation.save_world(
world_name="test_world",
sdf_content=world_content,
file_path=str(file_path)
)
assert result.success is True
assert "file_path" in result.data
assert file_path.exists()
assert file_path.read_text() == world_content
def test_save_world_creates_directory(self, tmp_path):
"""Test that save_world creates parent directories."""
nested_path = tmp_path / "nested" / "dir" / "test_world.sdf"
world_content = '<?xml version="1.0"?><sdf version="1.7"><world name="test"></world></sdf>'
result = world_generation.save_world(
world_name="test_world",
sdf_content=world_content,
file_path=str(nested_path)
)
assert result.success is True
assert nested_path.exists()
def test_save_world_invalid_content(self, tmp_path):
"""Test that invalid SDF content returns error."""
file_path = tmp_path / "test.sdf"
result = world_generation.save_world(
world_name="test",
sdf_content="not valid xml",
file_path=str(file_path)
)
assert result.success is False
assert "INVALID" in result.error_code or "VALIDATION" in result.error_code
class TestLoadWorld:
"""Test loading world files."""
def test_load_world_success(self, tmp_path):
"""Test loading world from file."""
world_content = '<?xml version="1.0"?><sdf version="1.7"><world name="test_world"></world></sdf>'
file_path = tmp_path / "test_world.sdf"
file_path.write_text(world_content)
result = world_generation.load_world(str(file_path))
assert result.success is True
assert "sdf_content" in result.data
assert "world_name" in result.data
assert result.data["sdf_content"] == world_content
assert result.data["world_name"] == "test_world"
def test_load_world_file_not_found(self):
"""Test loading non-existent file returns error."""
result = world_generation.load_world("/nonexistent/path/world.sdf")
assert result.success is False
assert "NOT_FOUND" in result.error_code or "FILE" in result.error_code
def test_load_world_invalid_sdf(self, tmp_path):
"""Test loading invalid SDF returns error."""
file_path = tmp_path / "invalid.sdf"
file_path.write_text("not valid xml")
result = world_generation.load_world(str(file_path))
assert result.success is False
assert "INVALID" in result.error_code or "PARSE" in result.error_code
class TestListWorldTemplates:
"""Test listing available world templates."""
def test_list_templates_success(self):
"""Test listing world templates."""
result = world_generation.list_world_templates()
assert result.success is True
assert "templates" in result.data
assert isinstance(result.data["templates"], list)
assert len(result.data["templates"]) > 0
def test_template_structure(self):
"""Test that templates have correct structure."""
result = world_generation.list_world_templates()
assert result.success is True
templates = result.data["templates"]
for template in templates:
assert "name" in template
assert "description" in template
assert isinstance(template["name"], str)
assert isinstance(template["description"], str)
def test_expected_templates(self):
"""Test that expected templates exist."""
result = world_generation.list_world_templates()
assert result.success is True
template_names = [t["name"] for t in result.data["templates"]]
# Should have at least these basic templates
assert "empty" in template_names
assert "with_ground" in template_names or "basic" in template_names
def test_template_has_parameters(self):
"""Test that templates list available parameters."""
result = world_generation.list_world_templates()
assert result.success is True
templates = result.data["templates"]
# At least one template should have parameters info
has_params = any("parameters" in t for t in templates)
assert has_params or len(templates) > 0 # Either has params or has templates
class TestPlaceBox:
"""Test box object placement."""
def test_place_box_basic(self):
"""Test basic box placement."""
result = world_generation.place_box(
name="test_box",
x=1.0, y=2.0, z=0.5,
width=1.0, height=1.0, depth=1.0
)
assert result.success is True
assert "sdf_content" in result.data
assert "name" in result.data
assert result.data["name"] == "test_box"
assert "<box>" in result.data["sdf_content"]
def test_place_box_with_color(self):
"""Test box with custom color."""
result = world_generation.place_box(
name="colored_box",
x=0, y=0, z=1,
width=1, height=1, depth=1,
color={"r": 1.0, "g": 0.0, "b": 0.0, "a": 1.0}
)
assert result.success is True
assert "ambient>1.0 0.0 0.0 1.0" in result.data["sdf_content"]
def test_place_box_static(self):
"""Test static box placement."""
result = world_generation.place_box(
name="static_box",
x=0, y=0, z=1,
width=1, height=1, depth=1,
static=True
)
assert result.success is True
assert "<static>true</static>" in result.data["sdf_content"]
def test_place_box_dynamic(self):
"""Test dynamic box placement."""
result = world_generation.place_box(
name="dynamic_box",
x=0, y=0, z=1,
width=1, height=1, depth=1,
static=False
)
assert result.success is True
assert ("<static>false</static>" in result.data["sdf_content"] or
"<static>true</static>" not in result.data["sdf_content"])
class TestPlaceSphere:
"""Test sphere object placement."""
def test_place_sphere_basic(self):
"""Test basic sphere placement."""
result = world_generation.place_sphere(
name="test_sphere",
x=1.0, y=2.0, z=0.5,
radius=0.5
)
assert result.success is True
assert "sdf_content" in result.data
assert "<sphere>" in result.data["sdf_content"]
assert "<radius>0.5</radius>" in result.data["sdf_content"]
def test_place_sphere_with_color(self):
"""Test sphere with custom color."""
result = world_generation.place_sphere(
name="colored_sphere",
x=0, y=0, z=1,
radius=0.5,
color={"r": 0.0, "g": 1.0, "b": 0.0, "a": 1.0}
)
assert result.success is True
assert "ambient>0.0 1.0 0.0 1.0" in result.data["sdf_content"]
class TestPlaceCylinder:
"""Test cylinder object placement."""
def test_place_cylinder_basic(self):
"""Test basic cylinder placement."""
result = world_generation.place_cylinder(
name="test_cylinder",
x=1.0, y=2.0, z=0.5,
radius=0.5,
length=2.0
)
assert result.success is True
assert "sdf_content" in result.data
assert "<cylinder>" in result.data["sdf_content"]
assert "<radius>0.5</radius>" in result.data["sdf_content"]
assert "<length>2.0</length>" in result.data["sdf_content"]
def test_place_cylinder_with_color(self):
"""Test cylinder with custom color."""
result = world_generation.place_cylinder(
name="colored_cylinder",
x=0, y=0, z=1,
radius=0.5,
length=2.0,
color={"r": 0.0, "g": 0.0, "b": 1.0, "a": 1.0}
)
assert result.success is True
assert "ambient>0.0 0.0 1.0 1.0" in result.data["sdf_content"]
class TestSpawnBox:
"""Test spawning box objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_box_success(self, mock_get_bridge):
"""Test successful box spawning."""
# Mock bridge
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_box(
name="test_box",
x=1.0, y=2.0, z=0.5,
width=1.0, height=1.0, depth=1.0
)
assert result.success is True
assert result.data["name"] == "test_box"
assert result.data["spawned"] is True
assert "position" in result.data
assert result.data["position"]["x"] == 1.0
assert result.data["position"]["y"] == 2.0
assert result.data["position"]["z"] == 0.5
# Verify bridge was called with correct SDF
mock_bridge.spawn_entity.assert_called_once()
call_args = mock_bridge.spawn_entity.call_args
assert call_args[1]["name"] == "test_box"
assert "<box>" in call_args[1]["xml_content"]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_box_with_color(self, mock_get_bridge):
"""Test box spawning with custom color."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_box(
name="red_box",
x=0, y=0, z=1,
width=1, height=1, depth=1,
color={"r": 1.0, "g": 0.0, "b": 0.0, "a": 1.0}
)
assert result.success is True
assert result.data["name"] == "red_box"
# Verify SDF contains color
call_args = mock_bridge.spawn_entity.call_args
assert "ambient>1.0 0.0 0.0 1.0" in call_args[1]["xml_content"]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_box_bridge_failure(self, mock_get_bridge):
"""Test handling of bridge spawn failure."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = False
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_box(
name="test_box",
x=1.0, y=2.0, z=0.5,
width=1.0, height=1.0, depth=1.0
)
assert result.success is False
assert "SPAWN_FAILED" in result.error_code
class TestSpawnSphere:
"""Test spawning sphere objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_sphere_success(self, mock_get_bridge):
"""Test successful sphere spawning."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_sphere(
name="test_sphere",
x=1.0, y=2.0, z=0.5,
radius=0.5
)
assert result.success is True
assert result.data["name"] == "test_sphere"
assert result.data["spawned"] is True
# Verify bridge was called with sphere SDF
mock_bridge.spawn_entity.assert_called_once()
call_args = mock_bridge.spawn_entity.call_args
assert "<sphere>" in call_args[1]["xml_content"]
assert "<radius>0.5</radius>" in call_args[1]["xml_content"]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_sphere_dynamic(self, mock_get_bridge):
"""Test spawning dynamic (physics-enabled) sphere."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_sphere(
name="ball",
x=1.0, y=1.0, z=2.0,
radius=0.5,
static=False
)
assert result.success is True
assert result.data["static"] is False
# Verify SDF contains inertial properties
call_args = mock_bridge.spawn_entity.call_args
assert "<inertial>" in call_args[1]["xml_content"]
class TestSpawnCylinder:
"""Test spawning cylinder objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_cylinder_success(self, mock_get_bridge):
"""Test successful cylinder spawning."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_cylinder(
name="test_cylinder",
x=1.0, y=2.0, z=0.5,
radius=0.5,
length=2.0
)
assert result.success is True
assert result.data["name"] == "test_cylinder"
assert result.data["spawned"] is True
# Verify bridge was called with cylinder SDF
mock_bridge.spawn_entity.assert_called_once()
call_args = mock_bridge.spawn_entity.call_args
assert "<cylinder>" in call_args[1]["xml_content"]
assert "<radius>0.5</radius>" in call_args[1]["xml_content"]
assert "<length>2.0</length>" in call_args[1]["xml_content"]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_cylinder_bridge_exception(self, mock_get_bridge):
"""Test handling of bridge exceptions."""
mock_bridge = Mock()
mock_bridge.spawn_entity.side_effect = Exception("Connection lost")
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_cylinder(
name="test_cylinder",
x=1.0, y=2.0, z=0.5,
radius=0.5,
length=2.0
)
assert result.success is False
assert "Connection lost" in result.error
class TestApplyForce:
"""Test applying force to objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_apply_force_success(self, mock_get_bridge):
"""Test successful force application."""
mock_bridge = Mock()
mock_bridge.set_entity_state.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.apply_force(
model_name="test_box",
force_x=10.0,
force_y=0.0,
force_z=0.0,
duration=1.0
)
assert result.success is True
assert result.data["model_name"] == "test_box"
assert result.data["force_applied"] is True
# Verify bridge was called with velocity
mock_bridge.set_entity_state.assert_called_once()
call_args = mock_bridge.set_entity_state.call_args
assert call_args[1]["name"] == "test_box"
assert "twist" in call_args[1]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_apply_force_bridge_failure(self, mock_get_bridge):
"""Test handling of bridge failure."""
mock_bridge = Mock()
mock_bridge.set_entity_state.return_value = False
mock_get_bridge.return_value = mock_bridge
result = world_generation.apply_force(
model_name="test_box",
force_x=10.0,
force_y=0.0,
force_z=0.0
)
assert result.success is False
assert "FORCE_APPLICATION_FAILED" in result.error_code
class TestApplyTorque:
"""Test applying torque to objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_apply_torque_success(self, mock_get_bridge):
"""Test successful torque application."""
mock_bridge = Mock()
mock_bridge.set_entity_state.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.apply_torque(
model_name="test_sphere",
torque_x=0.0,
torque_y=0.0,
torque_z=5.0,
duration=1.0
)
assert result.success is True
assert result.data["model_name"] == "test_sphere"
assert result.data["torque_applied"] is True
# Verify bridge was called with angular velocity
mock_bridge.set_entity_state.assert_called_once()
call_args = mock_bridge.set_entity_state.call_args
assert "twist" in call_args[1]
assert "angular" in call_args[1]["twist"]
class TestSetWind:
"""Test wind configuration helpers."""
def test_set_wind_configuration(self):
"""Test wind configuration helper."""
result = world_generation.set_wind(
linear_x=2.0,
linear_y=1.0,
linear_z=0.0
)
assert result.success is True
assert "wind_config" in result.data
assert result.data["wind_config"]["linear"]["x"] == 2.0
assert result.data["wind_config"]["linear"]["y"] == 1.0
assert "plugin_instructions" in result.data
def test_set_wind_zero_wind(self):
"""Test setting zero wind (calm conditions)."""
result = world_generation.set_wind(
linear_x=0.0,
linear_y=0.0,
linear_z=0.0
)
assert result.success is True
assert result.data["wind_config"]["linear"]["x"] == 0.0
class TestSpawnLight:
"""Test spawning lights in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_directional_light(self, mock_get_bridge):
"""Test spawning directional light (sun-like)."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_light(
name="sun_light",
light_type="directional",
position={"x": 0, "y": 0, "z": 10},
direction={"x": 0, "y": 0, "z": -1},
diffuse={"r": 1.0, "g": 1.0, "b": 1.0, "a": 1.0}
)
assert result.success is True
assert result.data["name"] == "sun_light"
assert result.data["light_type"] == "directional"
# Verify bridge was called
mock_bridge.spawn_entity.assert_called_once()
call_args = mock_bridge.spawn_entity.call_args
assert "<light" in call_args[1]["xml_content"]
assert "directional" in call_args[1]["xml_content"]
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_point_light(self, mock_get_bridge):
"""Test spawning point light (bulb-like)."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_light(
name="lamp_1",
light_type="point",
position={"x": 2, "y": 2, "z": 3},
diffuse={"r": 1.0, "g": 0.8, "b": 0.6, "a": 1.0},
attenuation_range=10.0
)
assert result.success is True
assert result.data["light_type"] == "point"
assert "attenuation_range" in result.data
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_spot_light(self, mock_get_bridge):
"""Test spawning spot light (flashlight-like)."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_light(
name="spotlight_1",
light_type="spot",
position={"x": 0, "y": 0, "z": 5},
direction={"x": 0, "y": 0, "z": -1},
spot_inner_angle=0.5,
spot_outer_angle=1.0
)
assert result.success is True
assert result.data["light_type"] == "spot"
class TestDeleteLight:
"""Test deleting lights from Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_delete_light_success(self, mock_get_bridge):
"""Test successful light deletion."""
mock_bridge = Mock()
mock_bridge.delete_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.delete_light("lamp_1")
assert result.success is True
assert result.data["name"] == "lamp_1"
assert result.data["deleted"] is True
mock_bridge.delete_entity.assert_called_once_with(name="lamp_1", timeout=10.0)
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_delete_light_failure(self, mock_get_bridge):
"""Test light deletion failure."""
mock_bridge = Mock()
mock_bridge.delete_entity.return_value = False
mock_get_bridge.return_value = mock_bridge
result = world_generation.delete_light("nonexistent_light")
assert result.success is False
assert "DELETE_FAILED" in result.error_code
class TestPlaceMesh:
"""Test mesh object placement."""
def test_place_mesh_basic(self):
"""Test basic mesh placement."""
result = world_generation.place_mesh(
name="custom_model",
mesh_file="models/my_model.dae",
x=1.0, y=2.0, z=0.5,
scale=1.0
)
assert result.success is True
assert result.data["name"] == "custom_model"
assert "sdf_content" in result.data
assert "my_model.dae" in result.data["sdf_content"]
assert "<mesh>" in result.data["sdf_content"]
def test_place_mesh_with_scale(self):
"""Test mesh with custom scaling."""
result = world_generation.place_mesh(
name="scaled_model",
mesh_file="models/chair.stl",
x=0, y=0, z=1,
scale=2.0
)
assert result.success is True
assert "scale>2.0 2.0 2.0" in result.data["sdf_content"]
def test_place_mesh_separate_collision(self):
"""Test mesh with separate collision mesh."""
result = world_generation.place_mesh(
name="complex_model",
mesh_file="models/visual.dae",
collision_mesh_file="models/collision.stl",
x=1, y=1, z=0
)
assert result.success is True
assert "visual.dae" in result.data["sdf_content"]
assert "collision.stl" in result.data["sdf_content"]
def test_place_mesh_invalid_format(self):
"""Test mesh with unsupported format."""
result = world_generation.place_mesh(
name="bad_model",
mesh_file="models/model.txt",
x=0, y=0, z=0
)
assert result.success is False
assert "INVALID_MESH_FORMAT" in result.error_code
class TestSpawnMesh:
"""Test spawning mesh objects in Gazebo."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_mesh_success(self, mock_get_bridge):
"""Test successful mesh spawning."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
result = world_generation.spawn_mesh(
name="custom_robot",
mesh_file="models/robot.dae",
x=1.0, y=2.0, z=0.5,
scale=1.0
)
assert result.success is True
assert result.data["name"] == "custom_robot"
assert result.data["spawned"] is True
# Verify bridge was called
mock_bridge.spawn_entity.assert_called_once()
call_args = mock_bridge.spawn_entity.call_args
assert "robot.dae" in call_args[1]["xml_content"]
class TestPlaceGrid:
"""Test grid-based object placement."""
def test_place_grid_basic(self):
"""Test basic grid placement."""
result = world_generation.place_grid(
object_type="box",
rows=3,
cols=3,
spacing=2.0,
object_params={"width": 1.0, "height": 1.0, "depth": 1.0}
)
assert result.success is True
assert len(result.data["objects"]) == 9 # 3x3 grid
assert result.data["rows"] == 3
assert result.data["cols"] == 3
def test_place_grid_with_offset(self):
"""Test grid with custom origin offset."""
result = world_generation.place_grid(
object_type="sphere",
rows=2,
cols=2,
spacing=3.0,
offset_x=5.0,
offset_y=5.0,
object_params={"radius": 0.5}
)
assert result.success is True
assert len(result.data["objects"]) == 4
# Check first object is offset correctly
first_obj = result.data["objects"][0]
assert first_obj["position"]["x"] == 5.0
assert first_obj["position"]["y"] == 5.0
def test_place_grid_invalid_object_type(self):
"""Test grid with invalid object type."""
result = world_generation.place_grid(
object_type="invalid_type",
rows=2,
cols=2,
spacing=2.0
)
assert result.success is False
assert "INVALID_OBJECT_TYPE" in result.error_code
class TestSpawnMultiple:
"""Test batch spawning for performance."""
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_multiple_success(self, mock_get_bridge):
"""Test successful batch spawning."""
mock_bridge = Mock()
mock_bridge.spawn_entity.return_value = True
mock_get_bridge.return_value = mock_bridge
objects = [
{"type": "box", "name": "box_1", "position": {"x": 0, "y": 0, "z": 0.5},
"params": {"width": 1, "height": 1, "depth": 1}},
{"type": "sphere", "name": "sphere_1", "position": {"x": 2, "y": 0, "z": 0.5},
"params": {"radius": 0.5}},
]
result = world_generation.spawn_multiple(objects)
assert result.success is True
assert result.data["total"] == 2
assert result.data["spawned"] == 2
assert result.data["failed"] == 0
# Verify bridge was called twice
assert mock_bridge.spawn_entity.call_count == 2
@patch('gazebo_mcp.tools.world_generation._get_bridge')
def test_spawn_multiple_partial_failure(self, mock_get_bridge):
"""Test batch spawning with partial failures."""
mock_bridge = Mock()
# First succeeds, second fails
mock_bridge.spawn_entity.side_effect = [True, False]
mock_get_bridge.return_value = mock_bridge
objects = [
{"type": "box", "name": "box_1", "position": {"x": 0, "y": 0, "z": 0.5},
"params": {"width": 1, "height": 1, "depth": 1}},
{"type": "box", "name": "box_2", "position": {"x": 2, "y": 0, "z": 0.5},
"params": {"width": 1, "height": 1, "depth": 1}},
]
result = world_generation.spawn_multiple(objects, continue_on_error=True)
assert result.success is True # Partial success
assert result.data["total"] == 2
assert result.data["spawned"] == 1
assert result.data["failed"] == 1
# ==============================================================================
# Phase 5A: High-Priority Enhancements - Tests
# ==============================================================================
class TestExtendedMaterials:
"""Test Phase 5A extended material library."""
def test_extended_material_count(self):
"""Test that we have 15+ materials."""
result = world_generation.list_materials()
assert result.success is True
assert len(result.data["materials"]) >= 15
def test_new_materials_exist(self):
"""Test that new Phase 5A materials are present."""
result = world_generation.list_materials()
materials = result.data["materials"]
# Phase 5A materials
new_materials = [
"asphalt", "gravel", "mud", "snow",
"metal", "carpet", "tile", "dirt", "wet_concrete"
]
for material in new_materials:
assert material in materials, f"Material '{material}' not found"
def test_rolling_friction_parameter(self):
"""Test that all materials have rolling_friction."""
result = world_generation.list_materials()
materials = result.data["materials"]
for name, props in materials.items():
assert "rolling_friction" in props, f"Material '{name}' missing rolling_friction"
assert isinstance(props["rolling_friction"], (int, float))
assert 0.0 <= props["rolling_friction"] <= 1.0
def test_wetness_parameter(self):
"""Test that materials have wetness parameter."""
result = world_generation.list_materials()
materials = result.data["materials"]
for name, props in materials.items():
assert "wetness" in props, f"Material '{name}' missing wetness"
assert isinstance(props["wetness"], (int, float))
assert 0.0 <= props["wetness"] <= 1.0
def test_asphalt_properties(self):
"""Test asphalt has correct properties for roads."""
result = world_generation.list_materials()
asphalt = result.data["materials"]["asphalt"]
# Asphalt should have high friction, low rolling friction
assert asphalt["friction"] >= 0.8
assert asphalt["rolling_friction"] <= 0.02
assert asphalt["restitution"] <= 0.1
def test_snow_properties(self):
"""Test snow has low friction and high wetness."""
result = world_generation.list_materials()
snow = result.data["materials"]["snow"]
# Snow should be slippery and wet
assert snow["friction"] <= 0.4
assert snow["wetness"] >= 0.7
def test_metal_properties(self):
"""Test metal has high friction and reflectivity."""
result = world_generation.list_materials()
metal = result.data["materials"]["metal"]
# Metal should have decent friction, low rolling friction
assert metal["friction"] >= 0.6
assert metal["rolling_friction"] <= 0.01
class TestBenchmarkWorlds:
"""Test Phase 5A benchmark world generation."""
def test_create_benchmark_world_nav2_standard(self):
"""Test creating standard nav2 benchmark."""
result = world_generation.create_benchmark_world(
benchmark_type="nav2_standard",
difficulty="medium"
)
assert result.success is True
assert "sdf_content" in result.data
assert result.data["benchmark_type"] == "nav2_standard"
assert result.data["difficulty"] == "medium"
def test_create_benchmark_world_with_seed(self):
"""Test that seed produces reproducible benchmarks."""
result1 = world_generation.create_benchmark_world(
benchmark_type="nav2_standard",
seed=42
)
result2 = world_generation.create_benchmark_world(
benchmark_type="nav2_standard",
seed=42
)
assert result1.success is True
assert result2.success is True
# Same seed should produce identical worlds
assert result1.data["sdf_content"] == result2.data["sdf_content"]
def test_create_benchmark_world_different_seeds(self):
"""Test that different seeds produce different obstacle configurations."""
result1 = world_generation.create_benchmark_world(
benchmark_type="nav2_standard",
seed=42
)
result2 = world_generation.create_benchmark_world(
benchmark_type="nav2_standard",
seed=123
)
assert result1.success is True
assert result2.success is True
# Different seeds should be recorded in metadata
assert result1.data["seed"] == 42
assert result2.data["seed"] == 123
# Both should have same number of obstacles (same difficulty)
assert result1.data["obstacles"] == result2.data["obstacles"]
def test_create_benchmark_world_obstacle_course(self):
"""Test creating obstacle course benchmark."""
result = world_generation.create_benchmark_world(
benchmark_type="obstacle_course",
difficulty="hard",
seed=42
)
assert result.success is True
assert result.data["benchmark_type"] == "obstacle_course"
assert "obstacles" in result.data
assert result.data["obstacles"] > 0
def test_create_benchmark_world_invalid_type(self):
"""Test error handling for invalid benchmark type."""
result = world_generation.create_benchmark_world(
benchmark_type="invalid_type"
)
assert result.success is False
assert "INVALID_BENCHMARK_TYPE" in result.error_code
def test_export_world_metadata(self):
"""Test exporting world metadata to JSON."""
result = world_generation.export_world_metadata(
world_name="test_world",
world_data={
"obstacles": 10,
"size": [20, 20],
"seed": 42
},
file_path="/tmp/test_metadata.json"
)
assert result.success is True
assert result.data["file_path"] == "/tmp/test_metadata.json"
assert result.data["format"] == "json"
# Verify file was created
import os
assert os.path.exists("/tmp/test_metadata.json")
class TestFogSystem:
"""Test Phase 5A fog and atmospheric effects."""
def test_set_fog_basic(self):
"""Test basic fog configuration."""
result = world_generation.set_fog(
density=0.5,
color={"r": 0.8, "g": 0.8, "b": 0.8}
)
assert result.success is True
assert result.data["density"] == 0.5
assert result.data["color"]["r"] == 0.8
def test_set_fog_sdf_content(self):
"""Test that fog generates valid SDF."""
result = world_generation.set_fog(density=0.3)
assert result.success is True
assert "sdf_content" in result.data
assert "<fog>" in result.data["sdf_content"]
assert "0.3" in result.data["sdf_content"]
def test_set_fog_zero_density(self):
"""Test fog with zero density (no fog)."""
result = world_generation.set_fog(density=0.0)
assert result.success is True
assert result.data["density"] == 0.0
assert result.data["enabled"] is False
def test_set_fog_invalid_density(self):
"""Test error handling for invalid density."""
result = world_generation.set_fog(density=1.5) # > 1.0
assert result.success is False
assert "INVALID_DENSITY" in result.error_code
class TestAdvancedWind:
"""Test Phase 5A enhanced wind system."""
def test_set_wind_with_turbulence(self):
"""Test wind with turbulence parameter."""
result = world_generation.set_wind(
linear_x=5.0,
linear_y=0.0,
linear_z=0.0,
turbulence=0.3
)
assert result.success is True
assert result.data["turbulence"] == 0.3
assert "plugin_xml" in result.data
def test_set_wind_with_gusts(self):
"""Test wind with gust system."""
result = world_generation.set_wind(
linear_x=5.0,
linear_y=0.0,
linear_z=0.0,
gust_enabled=True,
gust_period=10.0,
gust_magnitude=2.0
)
assert result.success is True
assert result.data["gust_enabled"] is True
assert result.data["gust_period"] == 10.0
assert result.data["gust_magnitude"] == 2.0
def test_set_wind_backward_compatible(self):
"""Test that old set_wind calls still work."""
# Phase 4 call (no turbulence/gusts)
result = world_generation.set_wind(
linear_x=3.0,
linear_y=1.0,
linear_z=0.0
)
assert result.success is True
# Should have default turbulence/gust values
assert "turbulence" in result.data
assert "gust_enabled" in result.data