Skip to content

Commit

Permalink
looking into better thread safety
Browse files Browse the repository at this point in the history
  • Loading branch information
AntoineRichard committed Sep 24, 2024
1 parent 610ee8a commit 2a67de8
Show file tree
Hide file tree
Showing 7 changed files with 24 additions and 12 deletions.
5 changes: 4 additions & 1 deletion src/environments/large_scale_lunar.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ def __init__(
large_scale_terrain: LargeScaleTerrainConf = None,
stellar_engine_settings: StellarEngineConf = None,
sun_settings: SunConf = None,
is_simulation_alive: callable = lambda: True,
**kwargs,
) -> None:
"""
Expand All @@ -48,12 +49,14 @@ def __init__(
env_settings (LargeScaleTerrainConf): The settings of the lab.
stellar_engine_settings (StellarEngineConf): The settings of the stellar engine.
sun_settings (SunConf): The settings of the sun.
is_simulation_alive (callable): function to check if the simulation is alive.
**kwargs: Arbitrary keyword arguments.
"""

super().__init__(**kwargs)
self.stage_settings = large_scale_terrain
self.sun_settings = sun_settings
self.is_simulation_alive = is_simulation_alive
if stellar_engine_settings is not None:
self.SE = StellarEngine(stellar_engine_settings)
self.enable_stellar_engine = True
Expand Down Expand Up @@ -133,7 +136,7 @@ def load(self) -> None:

self.build_scene()
# Instantiates the terrain manager
self.LSTM = LargeScaleTerrainManager(self.stage_settings)
self.LSTM = LargeScaleTerrainManager(self.stage_settings, is_simulation_alive=self.is_simulation_alive)
self.LSTM.build()
# Sets the sun using the stellar engine if enabled
if self.enable_stellar_engine:
Expand Down
6 changes: 4 additions & 2 deletions src/environments_wrappers/ros1/largescale_ros1.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

# Loads ROS1 dependent libraries
import rospy
from std_msgs.msg import Float32
from std_msgs.msg import Float32, ColorRGBA
from geometry_msgs.msg import Pose


Expand All @@ -23,6 +23,7 @@ class ROS_LargeScaleManager(ROS_BaseManager):
def __init__(
self,
environment_cfg: dict = None,
is_simulation_alive: callable = lambda: True,
**kwargs,
) -> None:
"""
Expand All @@ -31,11 +32,12 @@ def __init__(
Args:
environment_cfg (dict): Environment configuration dictionary.
flares_cfg (dict): Lens flares configuration dictionary.
is_simulation_alive (callable): function to check if the simulation is alive.
**kwargs: Additional keyword arguments.
"""

super().__init__(environment_cfg=environment_cfg, **kwargs)
self.LC = LargeScaleController(**environment_cfg)
self.LC = LargeScaleController(**environment_cfg, is_simulation_alive=is_simulation_alive)
self.LC.load()

self.projector_subs = []
Expand Down
4 changes: 3 additions & 1 deletion src/environments_wrappers/ros2/largescale_ros2.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,18 +24,20 @@ class ROS_LargeScaleManager(ROS_BaseManager):
def __init__(
self,
environment_cfg: dict = None,
is_simulation_alive: callable = lambda: True,
**kwargs,
) -> None:
"""
Initializes the environment manager.
Args:
environment_cfg (dict): Environment configuration.
is_simulation_alive (callable): function to check if the simulation is alive.
**kwargs: Additional arguments.
"""

super().__init__(environment_cfg=environment_cfg, **kwargs)
self.LC = LargeScaleController(**environment_cfg)
self.LC = LargeScaleController(**environment_cfg, is_simulation_alive=is_simulation_alive)
self.LC.load()

self.create_subscription(Float32, "/OmniLRS/Sun/Intensity", self.set_sun_intensity, 1)
Expand Down
8 changes: 5 additions & 3 deletions src/environments_wrappers/ros2/simulation_manager_ros2.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

from threading import Thread

from omni.isaac.kit import SimulationApp
from omni.isaac.core import World
from typing import Union
import omni
Expand Down Expand Up @@ -92,6 +93,7 @@ def register(
def __call__(
self,
cfg: dict,
is_simulation_alive: callable,
) -> Union[ROS_LunalabManager, ROS_LunaryardManager]:
"""
Returns an instance of the lab manager corresponding to the environment name.
Expand All @@ -105,7 +107,7 @@ def __call__(

return self._lab_managers[cfg["environment"]["name"]](
environment_cfg=cfg["environment"],
flares_cfg=cfg["rendering"]["lens_flares"],
is_simulation_alive=is_simulation_alive,
)


Expand All @@ -128,7 +130,7 @@ class ROS2_SimulationManager:
def __init__(
self,
cfg: dict,
simulation_app,
simulation_app: SimulationApp,
) -> None:
"""
Initializes the simulation.
Expand Down Expand Up @@ -158,7 +160,7 @@ def __init__(
self.rate = Rate(is_disabled=True)

# Lab manager thread
self.ROSLabManager = ROS2_LMF(cfg)
self.ROSLabManager = ROS2_LMF(cfg, self.simulation_app.is_running)
exec1 = Executor()
exec1.add_node(self.ROSLabManager)
self.exec1_thread = Thread(target=exec1.spin, daemon=True, args=())
Expand Down
3 changes: 2 additions & 1 deletion src/environments_wrappers/sdg/simulation_manager_sdg.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@ def __init__(self, cfg, simulation_app) -> None:

def run_simulation(self) -> None:
"""
Runs the simulation."""
Runs the simulation.
"""

self.timeline.play()
while self.simulation_app.is_running() and (self.count < self.generation_settings.num_images):
Expand Down
5 changes: 3 additions & 2 deletions src/terrain_management/large_scale_terrain/map_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,14 +61,15 @@ class MapManager:
interract with the DEMs.
"""

def __init__(self, map_manager_settings: MapManagerConf) -> None:
def __init__(self, map_manager_settings: MapManagerConf, is_simulation_alive: callable = lambda: True) -> None:
"""
Args:
hrdem_settings (HighResDEMGenConf): settings for the high resolution DEM generation.
map_manager_settings (MapManagerConf): settings for the map manager.
is_simulation_alive (callable): function to check if the simulation is alive.
"""

self.hr_dem_settings = map_manager_settings.hrdem_settings
self.is_simulation_alive = is_simulation_alive
self.settings = map_manager_settings
self.lr_dem = None

Expand Down
5 changes: 3 additions & 2 deletions src/terrain_management/large_scale_terrain_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,10 @@ class LargeScaleTerrainManager:
def __init__(
self,
settings: LargeScaleTerrainConf,
is_simulation_alive: callable = lambda: True,
):
self.settings = settings

self.is_simulation_alive = is_simulation_alive
self.last_update_coordinates = None

def build_configs(self):
Expand All @@ -50,7 +51,7 @@ def build_managers(self):
self.build_rock_manager()

def build_map_manager(self):
self.map_manager = MapManager(self.mapmanager_cfg)
self.map_manager = MapManager(self.mapmanager_cfg, is_simulation_alive = self.is_simulation_alive)
self.map_manager.load_lr_dem_by_name(self.settings.lr_dem_name)
self.map_manager.initialize_hr_dem(self.settings.starting_position)

Expand Down

0 comments on commit 2a67de8

Please sign in to comment.