Skip to content
Open
Show file tree
Hide file tree
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
9 changes: 6 additions & 3 deletions server/src/xbot2_gui_server/dashboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
12 changes: 6 additions & 6 deletions server/src/xbot2_gui_server/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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
Expand All @@ -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():
Expand All @@ -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():
Expand All @@ -154,15 +154,15 @@ 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
ext = ParameterHandler(srv, cfg.get('parameters', {}))
extensions.append(ext)
print(ext)
except BaseException as e:
print('Exception ', type(e), e)
print('ParameterHandler Exception ', type(e), e)

srv.extensions = extensions

Expand Down