From 3b1fa84e72692cbff1b3abc57422896a670855ee Mon Sep 17 00:00:00 2001 From: Davide Torielli Date: Mon, 18 Nov 2024 13:25:39 +0000 Subject: [PATCH 1/2] ros2 api --- server/src/xbot2_gui_server/dashboard.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/server/src/xbot2_gui_server/dashboard.py b/server/src/xbot2_gui_server/dashboard.py index 0717b6f..776c82c 100644 --- a/server/src/xbot2_gui_server/dashboard.py +++ b/server/src/xbot2_gui_server/dashboard.py @@ -2,7 +2,8 @@ from aiohttp import web import json -import rospy +import rclpy +from rclpy.node import Node from std_srvs.srv import SetBool, Trigger from std_msgs.msg import String from geometry_msgs.msg import TwistStamped, Twist @@ -54,7 +55,8 @@ def __init__(self, srv: ServerBase, config=dict()) -> None: 'dashboard_start') # subscribe to stats - self.stats_sub = rospy.Subscriber('xbotcore/statistics', Statistics2, self.on_stats_recv) + self.node = rclpy.create_node('dashboard') + self.stats_sub = self.node.create_subscription(Statistics2, 'xbotcore/statistics', self.on_stats_recv, 10) self.stats: Statistics2 = None # launcher @@ -210,7 +212,8 @@ async def dashboard_start(self, request: web.Request): async def plugin_switch(self, plugin_name, switch_flag): - switch = rospy.ServiceProxy(f'xbotcore/{plugin_name}/switch', service_class=SetBool) + self.cli = self.create_client(AddTwoInts, 'add_two_ints') + switch = self.node.create_client(SetBool, f'xbotcore/{plugin_name}/switch') await utils.to_thread(switch.wait_for_service, timeout=1.0) res = await utils.to_thread(switch, switch_flag) return res.success From 6f3f69ea85cce413d5fa5cafa0272c7434d7290b Mon Sep 17 00:00:00 2001 From: Davide Torielli Date: Mon, 18 Nov 2024 13:25:54 +0000 Subject: [PATCH 2/2] more verbose print exceptions --- server/src/xbot2_gui_server/main.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/server/src/xbot2_gui_server/main.py b/server/src/xbot2_gui_server/main.py index 93135aa..b8e6954 100644 --- a/server/src/xbot2_gui_server/main.py +++ b/server/src/xbot2_gui_server/main.py @@ -94,7 +94,7 @@ async def load_extensions(): except ModuleNotFoundError: pass except BaseException as e: - print('Exception ', type(e), e) + print('Launcher Exception ', type(e), e) # cartesian try: @@ -113,7 +113,7 @@ async def load_extensions(): except ModuleNotFoundError: pass except BaseException as e: - print('Exception ', type(e), e) + print('SpeechHandler Exception ', type(e), e) # visual @@ -123,7 +123,7 @@ async def load_extensions(): extensions.append(ext) print(ext) except BaseException as e: - print('Exception ', type(e), e) + print('VisualHandler Exception ', type(e), e) # concert if 'concert' in cfg.keys(): @@ -133,7 +133,7 @@ async def load_extensions(): extensions.append(ext) print(ext) except BaseException as e: - print('Exception ', type(e), e) + print('ConcertHandler Exception ', type(e), e) # ecat if 'ecat' in cfg.keys(): @@ -154,7 +154,7 @@ async def load_extensions(): extensions.append(ext) print(ext) except BaseException as e: - print('Exception ', type(e), e) + print('DashboardHandler Exception ', type(e), e) try: from .parameters import ParameterHandler @@ -162,7 +162,7 @@ async def load_extensions(): extensions.append(ext) print(ext) except BaseException as e: - print('Exception ', type(e), e) + print('ParameterHandler Exception ', type(e), e) srv.extensions = extensions