Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS2 Drones (PX4 + AS2) ILauncher #73

Merged
merged 1 commit into from
Aug 17, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
58 changes: 58 additions & 0 deletions manager/manager/launcher/launcher_drones_ros2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
import os
import subprocess
from src.manager.manager.launcher.launcher_interface import ILauncher, LauncherException
from src.manager.manager.docker_thread.docker_thread import DockerThread
from typing import List, Any
import time
Copy link
Collaborator Author

@pawanw17 pawanw17 Aug 17, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@pariaspe this import needs to be removed.


class LauncherDronesRos2(ILauncher):
exercise_id: str
type: str
module: str
resource_folders: List[str]
model_folders: List[str]
plugin_folders: List[str]
world_file: str
running = False
threads: List[Any] = []

def run(self, callback):

# expand variables in configuration paths
self._set_environment()
world_file = os.path.expandvars(self.world_file)

# Launching MicroXRCE and Aerostack2 nodes
as2_launch_cmd = f"ros2 launch jderobot_drones as2_default_classic_gazebo.launch.py world_file:={world_file}"

as2_launch_thread = DockerThread(as2_launch_cmd)
as2_launch_thread.start()
self.threads.append(as2_launch_thread)

# Launching gzserver and PX4
px4_launch_cmd = f"$AS2_GZ_ASSETS_SCRIPT_PATH/default_run.sh {world_file}"

px4_launch_thread = DockerThread(px4_launch_cmd)
px4_launch_thread.start()
self.threads.append(px4_launch_thread)

self.running = True

def is_running(self):
return True

def terminate(self):
if self.is_running():
for thread in self.threads:
thread.terminate()
thread.join()
self.running = False

def _set_environment(self):
resource_folders = [os.path.expandvars(path) for path in self.resource_folders]
model_folders = [os.path.expandvars(path) for path in self.model_folders]
plugin_folders = [os.path.expandvars(path) for path in self.plugin_folders]

os.environ["GAZEBO_RESOURCE_PATH"] = f"{os.environ.get('GAZEBO_RESOURCE_PATH', '')}:{':'.join(resource_folders)}"
os.environ["GAZEBO_MODEL_PATH"] = f"{os.environ.get('GAZEBO_MODEL_PATH', '')}:{':'.join(model_folders)}"
os.environ["GAZEBO_PLUGIN_PATH"] = f"{os.environ.get('GAZEBO_PLUGIN_PATH', '')}:{':'.join(plugin_folders)}"