Skip to content

Commit

Permalink
Merge pull request #131 from JdeRobot/new_follow_person
Browse files Browse the repository at this point in the history
[Follow person] Superthin support
  • Loading branch information
OscarMrZ authored Mar 24, 2024
2 parents 5c7d454 + f5b3800 commit 8320633
Show file tree
Hide file tree
Showing 8 changed files with 396 additions and 246 deletions.
12 changes: 7 additions & 5 deletions manager/libs/applications/compatibility/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,14 @@


class Server(threading.Thread):
def __init__(self, port, callback,):
def __init__(
self,
port,
callback,
):
super().__init__()
self.update_callback = callback
self.server = WebsocketServer(port=port, host='127.0.0.1')
self.server = WebsocketServer(port=port, host="127.0.0.1")
self.server.set_fn_new_client(self.on_open)
self.server.set_fn_client_left(self.on_close)
self.server.set_fn_message_received(self.on_message)
Expand Down Expand Up @@ -39,9 +43,7 @@ def send(self, data):
def on_message(self, client, server, message):
payload = json.loads(message)
self.update_callback(payload)
server.send_message(client, "#ack")
LogManager.logger.debug(
f"Message received from template: {message[:30]}")
LogManager.logger.debug(f"Message received from template: {message[:30]}")

def on_close(self, client, server):
LogManager.logger.info("Connection with client closed")
Expand Down
20 changes: 11 additions & 9 deletions manager/manager/launcher/launcher_console.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
from src.manager.manager.launcher.launcher_interface import ILauncher
from src.manager.manager.docker_thread.docker_thread import DockerThread
from src.manager.manager.vnc.vnc_server import Vnc_server
from src.manager.libs.process_utils import check_gpu_acceleration
from src.manager.libs.process_utils import check_gpu_acceleration
import os
import stat
from typing import List, Any
Expand All @@ -11,22 +11,24 @@ class LauncherConsole(ILauncher):
display: str
internal_port: int
external_port: int
running:bool = False
running: bool = False
threads: List[Any] = []
console_vnc: Any = Vnc_server()

def run(self, callback):
DRI_PATH = os.path.join("/dev/dri", os.environ.get("DRI_NAME", "card0"))
ACCELERATION_ENABLED = False



if (ACCELERATION_ENABLED):
self.console_vnc.start_vnc_gpu(self.display, self.internal_port, self.external_port,DRI_PATH)
if ACCELERATION_ENABLED:
self.console_vnc.start_vnc_gpu(
self.display, self.internal_port, self.external_port, DRI_PATH
)
# Write display config and start the console
console_cmd = f"export VGL_DISPLAY={DRI_PATH}; export DISPLAY={self.display}; vglrun xterm -fullscreen -sb -fa 'Monospace' -fs 10 -bg black -fg white"
else:
self.console_vnc.start_vnc(self.display, self.internal_port, self.external_port)
self.console_vnc.start_vnc(
self.display, self.internal_port, self.external_port
)
# Write display config and start the console
console_cmd = f"export DISPLAY={self.display};xterm -geometry 100x10+0+0 -fa 'Monospace' -fs 10 -bg black -fg white"

Expand All @@ -35,7 +37,7 @@ def run(self, callback):
self.threads.append(console_thread)

self.running = True

def check_device(self, device_path):
try:
return stat.S_ISCHR(os.lstat(device_path)[stat.ST_MODE])
Expand All @@ -53,4 +55,4 @@ def terminate(self):
self.running = False

def died(self):
pass
pass
27 changes: 13 additions & 14 deletions manager/manager/launcher/launcher_gazebo_view.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
from src.manager.manager.launcher.launcher_interface import ILauncher
from src.manager.manager.docker_thread.docker_thread import DockerThread
from src.manager.manager.vnc.vnc_server import Vnc_server
from src.manager.libs.process_utils import wait_for_process_to_start, check_gpu_acceleration
from src.manager.libs.process_utils import (
wait_for_process_to_start,
check_gpu_acceleration,
)
import subprocess
import time
import os
Expand Down Expand Up @@ -29,17 +32,15 @@ def run(self, callback):
if ACCELERATION_ENABLED:
# Starts xserver, x11vnc and novnc
self.gz_vnc.start_vnc_gpu(
self.display, self.internal_port, self.external_port, DRI_PATH)
self.display, self.internal_port, self.external_port, DRI_PATH
)
# Write display config and start gzclient
gzclient_cmd = (
f"export DISPLAY={self.display}; {gzclient_config_cmds} export VGL_DISPLAY={DRI_PATH}; vglrun gzclient --verbose")
gzclient_cmd = f"export DISPLAY={self.display}; {gzclient_config_cmds} export VGL_DISPLAY={DRI_PATH}; vglrun gzclient --verbose"
else:
# Starts xserver, x11vnc and novnc
self.gz_vnc.start_vnc(
self.display, self.internal_port, self.external_port)
self.gz_vnc.start_vnc(self.display, self.internal_port, self.external_port)
# Write display config and start gzclient
gzclient_cmd = (
f"export DISPLAY={self.display}; {gzclient_config_cmds} gzclient --verbose")
gzclient_cmd = f"export DISPLAY={self.display}; {gzclient_config_cmds} gzclient --verbose"

gzclient_thread = DockerThread(gzclient_cmd)
gzclient_thread.start()
Expand Down Expand Up @@ -70,14 +71,12 @@ def died(self):
pass

def get_dri_path(self):
directory_path = '/dev/dri'
directory_path = "/dev/dri"
dri_path = ""
if os.path.exists(directory_path) and os.path.isdir(directory_path):
files = os.listdir(directory_path)
if ("card1" in files):
dri_path = os.path.join(
"/dev/dri", os.environ.get("DRI_NAME", "card1"))
if "card1" in files:
dri_path = os.path.join("/dev/dri", os.environ.get("DRI_NAME", "card1"))
else:
dri_path = os.path.join(
"/dev/dri", os.environ.get("DRI_NAME", "card0"))
dri_path = os.path.join("/dev/dri", os.environ.get("DRI_NAME", "card0"))
return dri_path
59 changes: 43 additions & 16 deletions manager/manager/launcher/launcher_ros2_api.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,14 @@

import logging


class LauncherRos2Api(ILauncher):
type: str
module: str
launch_file: str
threads: List[Any] = []

def run(self,callback):
def run(self, callback):
DRI_PATH = os.path.join("/dev/dri", os.environ.get("DRI_NAME", "card0"))
ACCELERATION_ENABLED = self.check_device(DRI_PATH)

Expand All @@ -26,14 +27,16 @@ def run(self,callback):
xserver_thread.start()
self.threads.append(xserver_thread)

if (ACCELERATION_ENABLED):
exercise_launch_cmd = f"export VGL_DISPLAY={DRI_PATH}; vglrun ros2 launch {self.launch_file}"
if ACCELERATION_ENABLED:
exercise_launch_cmd = (
f"export VGL_DISPLAY={DRI_PATH}; vglrun ros2 launch {self.launch_file}"
)
else:
exercise_launch_cmd = f"ros2 launch {self.launch_file}"

exercise_launch_thread = DockerThread(exercise_launch_cmd)
exercise_launch_thread.start()

def check_device(self, device_path):
try:
return stat.S_ISCHR(os.lstat(device_path)[stat.ST_MODE])
Expand All @@ -45,15 +48,39 @@ def terminate(self):
for thread in self.threads:
thread.terminate()
thread.join()

kill_cmd = 'pkill -9 -f '
cmd = kill_cmd + 'gzserver'
subprocess.call(cmd, shell=True, stdout=subprocess.PIPE, bufsize=1024, universal_newlines=True)
cmd = kill_cmd + 'spawn_model.launch.py'
subprocess.call(cmd, shell=True, stdout=subprocess.PIPE, bufsize=1024, universal_newlines=True)

kill_cmd = 'pkill -9 -f '
cmd = kill_cmd + 'gzserver'
subprocess.call(cmd, shell=True, stdout=subprocess.PIPE, bufsize=1024, universal_newlines=True)
cmd = kill_cmd + 'spawn_model.launch.py'
subprocess.call(cmd, shell=True, stdout=subprocess.PIPE, bufsize=1024, universal_newlines=True)

kill_cmd = "pkill -9 -f "
cmd = kill_cmd + "gzserver"
subprocess.call(
cmd,
shell=True,
stdout=subprocess.PIPE,
bufsize=1024,
universal_newlines=True,
)
cmd = kill_cmd + "spawn_model.launch.py"
subprocess.call(
cmd,
shell=True,
stdout=subprocess.PIPE,
bufsize=1024,
universal_newlines=True,
)

kill_cmd = "pkill -9 -f "
cmd = kill_cmd + "gzserver"
subprocess.call(
cmd,
shell=True,
stdout=subprocess.PIPE,
bufsize=1024,
universal_newlines=True,
)
cmd = kill_cmd + "spawn_model.launch.py"
subprocess.call(
cmd,
shell=True,
stdout=subprocess.PIPE,
bufsize=1024,
universal_newlines=True,
)
Loading

0 comments on commit 8320633

Please sign in to comment.