diff --git a/route_guidance_ros/scripts/Navigation.py b/route_guidance_ros/scripts/Navigation.py index fb38f75cab2922e85ac0d5314353937ab202bb93..593f1fc51f1be970074315a78ab8d245d4f11771 100755 --- a/route_guidance_ros/scripts/Navigation.py +++ b/route_guidance_ros/scripts/Navigation.py @@ -69,11 +69,11 @@ class Event(RoIS_Common.Event): self._component = c self.event_queue = queue.Queue() - # def poll_event(self): - # msg = self.event_queue.get() - # return msg from goal_sender_ros import GoalSenderROS +import xmlrpclib + +from pyrois.RoIS_Common import Component_Status class Navigation(Event, Command, Query): def __init__(self, c, robot_name): @@ -83,8 +83,12 @@ class Navigation(Event, Command, Query): self._component.Target_Position = [""] self._component.Time_Limit = 10 self._component.Routing_Policy = "" + self.latest_nav_state = Component_Status.UNINITIALIZED def set_parameter(self, target_position, time_limit, routing_policy): + # Put event + self.latest_nav_state = Component_Status.BUSY + self._goal_sender.send_goal(target_position) status = RoIS_HRI.ReturnCode_t.OK.value return status diff --git a/route_guidance_ros/scripts/Navigation_client.py b/route_guidance_ros/scripts/Navigation_client.py index fc616a489b251b996f217c27261883fc8672c39c..3212bc1738d16900d3f67f2515c4e3b7fc118149 100644 --- a/route_guidance_ros/scripts/Navigation_client.py +++ b/route_guidance_ros/scripts/Navigation_client.py @@ -72,29 +72,6 @@ class Event(RoIS_Common.Event): # if logger is not None: # self.logger = logger - # def start_th(self): - # self.th = threading.Thread(target=self.event_loop) - # self.th.start() - - # def event_loop(self): - # """event_loop - # """ - # while True: - # try: - # self.poll_event() - # except ConnectionRefusedError: - # break - - # def poll_event(self): - # """poll_event - # """ - # msg = self._e_proxy.poll_event() - # (params, methodname) = xmlrpc.client.loads(msg) - # #self.logger.debug('poll_event: '+methodname) - # print(params,methodname) - # if methodname == 'speech_recognized': - # self.speech_recognized(params[0], params[1]) - class Navigation_Client(Command, Query, Event): """Navigation_Client @@ -104,4 +81,3 @@ class Navigation_Client(Command, Query, Event): self._proxy = xmlrpc.client.ServerProxy(self._uri) self._e_proxy = xmlrpc.client.ServerProxy(self._uri) self.events = [] - # self.start_th() diff --git a/route_guidance_ros/scripts/VirtualNavigation.py b/route_guidance_ros/scripts/VirtualNavigation.py index 056888befdfc476aed8163abce0c114cf859146a..0abc14dfab16fc9b36468bfdc0c98e87d1cb536d 100755 --- a/route_guidance_ros/scripts/VirtualNavigation.py +++ b/route_guidance_ros/scripts/VirtualNavigation.py @@ -69,11 +69,14 @@ class Event(RoIS_Common.Event): self._component = c self.event_queue = queue.Queue() - # def poll_event(self): - # msg = self.event_queue.get() - # return msg + def poll_event(self): + msg = self.event_queue.get() + return msg from goal_sender_ros import GoalSenderROS +from pyrois.RoIS_Common import Component_Status + +import xmlrpclib class VirtualNavigation(Event, Command, Query): def __init__(self, c, robot_names): @@ -82,16 +85,24 @@ class VirtualNavigation(Event, Command, Query): self._component.Target_Position = [""] self._component.Time_Limit = 10 self._component.Routing_Policy = "" + self.robot_goal_table = {} + self.nav_state_table = \ + {robot_name : Component_Status.UNINITIALIZED for robot_name in robot_names} def set_parameter(self, target_position, time_limit, routing_policy): - self._component.send_goal_to_nearest_robot(target_position) + nearest_robot = self._component.get_nearest_robotname(target_position) + th = threading.Thread( + target=self.send_goal_and_event, + args=(target_position, nearest_robot)) + th.daemon = True + th.start() status = RoIS_HRI.ReturnCode_t.OK.value return status - def component_status(self): - status = RoIS_HRI.ReturnCode_t.OK.value - c_status = self._goal_sender.get_goalsender_state().value - return (status, c_status) + def send_goal_and_event(self, goal, robot_name): + status = self._component.send_goal_to_robot_async(goal, robot_name) + msg = xmlrpclib.dumps((goal, robot_name), 'completed') + self.event_queue.put(msg) def event_dispatch(n): @@ -105,6 +116,7 @@ from geometry_msgs.msg import PoseWithCovarianceStamped from functools import partial + class Component(object): def __init__(self, robot_names): self.__robot_names = robot_names @@ -116,12 +128,10 @@ class Component(object): PoseWithCovarianceStamped, partial(self.update_position, robot_name)) - def update_position(self, robot_name, amcl_pose): pos = amcl_pose.pose.pose.position self.__robot_positions[robot_name] = np.array([pos.x, pos.y]) - def send_goal_to_nearest_robot(self, dest): dest = np.array(dest) distance_table = \ @@ -129,6 +139,24 @@ class Component(object): nearest_robot = min(distance_table, key=distance_table.get) print("nearest_robot is ", nearest_robot) self.__goal_senders[nearest_robot].send_goal(dest.tolist()) + return nearest_robot + + def get_nearest_robotname(self, dest): + dest = np.array(dest) + distance_table = \ + {name: np.linalg.norm(dest - pos) for name, pos in self.__robot_positions.items()} + nearest_robot = min(distance_table, key=distance_table.get) + return nearest_robot + + def send_goal_to_robot(self, goal, robot): + self.__goal_senders[robot].send_goal(goal) + + def get_nav_state(self, robot_name): + goal_sender = self.__goal_senders[robot_name] + return goal_sender.get_goalsender_state() + + def send_goal_to_robot_async(self, goal, robot): + return self.__goal_senders[robot].send_goal_and_wait(goal) def example_n(port, robot_names): diff --git a/route_guidance_ros/scripts/VirtualNavigation_client.py b/route_guidance_ros/scripts/VirtualNavigation_client.py index be14ab33d157a3c6cb13b22fff2fa61e70bf6ed5..54d443696f6e7802d18cd1e5a26872d840712b96 100644 --- a/route_guidance_ros/scripts/VirtualNavigation_client.py +++ b/route_guidance_ros/scripts/VirtualNavigation_client.py @@ -61,6 +61,7 @@ class Query(RoIS_Common.Query): (status, target_position, time_limit, routing_policy) = self._proxy.get_parameter() return (RoIS_HRI.ReturnCode_t(status), target_position, time_limit, routing_policy) +import time class Event(RoIS_Common.Event): """Event @@ -72,36 +73,45 @@ class Event(RoIS_Common.Event): # if logger is not None: # self.logger = logger - # def start_th(self): - # self.th = threading.Thread(target=self.event_loop) - # self.th.start() - - # def event_loop(self): - # """event_loop - # """ - # while True: - # try: - # self.poll_event() - # except ConnectionRefusedError: - # break - - # def poll_event(self): - # """poll_event - # """ - # msg = self._e_proxy.poll_event() - # (params, methodname) = xmlrpc.client.loads(msg) - # #self.logger.debug('poll_event: '+methodname) - # print(params,methodname) - # if methodname == 'speech_recognized': - # self.speech_recognized(params[0], params[1]) + def start_th(self): + self.th = threading.Thread(target=self.event_loop) + self.th.start() + + def event_loop(self): + """event_loop + """ + while True: + time.sleep(1) + try: + self.poll_event() + except xmlrpc.client.ProtocolError as e: + print("ProtocolError", e) + continue + except ConnectionRefusedError as e: + print("ConnectionRefusedError ", e) + continue + + def poll_event(self): + """poll_event + """ + msg = self._e_proxy.poll_event() + (params, methodname) = xmlrpc.client.loads(msg) class VirtualNavigation_Client(Command, Query, Event): """VirtualNavigation_Client """ - def __init__(self, uri): + def __init__(self, uri, engine_event_queue): self._uri = uri self._proxy = xmlrpc.client.ServerProxy(self._uri) self._e_proxy = xmlrpc.client.ServerProxy(self._uri) self.events = [] - # self.start_th() + self.engine_event_queue = engine_event_queue + self.start_th() + + def poll_event(self): + """poll_event + """ + msg = self._e_proxy.poll_event() + (params, methodname) = xmlrpc.client.loads(msg) + self.engine_event_queue.put(msg) diff --git a/route_guidance_ros/scripts/goal_sender_ros.py b/route_guidance_ros/scripts/goal_sender_ros.py index 3b69730de70dcd80a734b54481cd6971c7dbb20c..d7f6f355f14ec05c619b6c85f8b880277fe1b8da 100644 --- a/route_guidance_ros/scripts/goal_sender_ros.py +++ b/route_guidance_ros/scripts/goal_sender_ros.py @@ -48,6 +48,12 @@ class GoalSenderROS(object): goal = pose_to_goal(pose) self.action_client.send_goal(goal) + def send_goal_and_wait(self, pose_xy): + pose_xy.append(0) + pose = [pose_xy, (0.0, 0.0, 0.0, 1.0)] + goal = pose_to_goal(pose) + return self.action_client.send_goal_and_wait(goal) + def get_goalsender_state(self): state = self.action_client.get_state() return GoalSenderROS.GoalSenderState[state] diff --git a/route_guidance_ros/scripts/toplevel_engine.py b/route_guidance_ros/scripts/main_engine.py similarity index 78% rename from route_guidance_ros/scripts/toplevel_engine.py rename to route_guidance_ros/scripts/main_engine.py index 77b280b19908634cd6f0bc3f9065fc90ca6e26b4..f76f9e9df4e9436e1dda4d99c33de02c2a3c6286 100644 --- a/route_guidance_ros/scripts/toplevel_engine.py +++ b/route_guidance_ros/scripts/main_engine.py @@ -14,9 +14,12 @@ from __future__ import print_function import os import sys +import queue import numpy as np +import threading from pyrois import RoIS_HRI +from pyrois.Service_Application_Base_example import Service_Application_Base if sys.version_info.major == 2: import SocketServer @@ -167,46 +170,62 @@ class EventIF(RoIS_HRI.EventIF): from VirtualNavigation_client import VirtualNavigation_Client as VNavClient from sub_engine_client import IF as EngineClient +from pyrois.RoIS_Common import Component_Status +import time -class IF(SystemIF, CommandIF, QueryIF, EventIF): +class IF(SystemIF, CommandIF, QueryIF, EventIF, Service_Application_Base): """IF """ def __init__(self, Engine): super().__init__(Engine) self.command_id = 0 + self.event_queue = queue.Queue() + self.component_event_queue = queue.Queue() self.component_clients = { - 'Navigation': VNavClient('http://localhost:8041') + 'Navigation': VNavClient('http://localhost:8041', self.component_event_queue) } self.engine_clients = { 'robot1': EngineClient('http://localhost:8010'), 'robot2': EngineClient('http://localhost:8020'), 'robot3': EngineClient('http://localhost:8030') } + self.init_pos_table = { + 'robot1': (0.0, 0.0 ), + 'robot2': (10.0, 0.0 ), + 'robot3': (0.0, 10.0) + } + self.goal_command_table = {} for engine_client in self.engine_clients.values(): engine_client.connect() def set_parameter(self, component_ref, parameters): - print("Using VirtualNavigation") target_component = self.component_clients[component_ref] - status = target_component.set_parameter(*parameters).value self.command_id += 1 + status = target_component.set_parameter(*parameters).value + th = threading.Thread( + target=self.analyze_c_status, + daemon=True, + args=(self.component_clients[component_ref], str(self.command_id))) + th.start() + goal = parameters[0] + goal.append(0) + self.goal_command_table[str(goal)] = str(self.command_id) return (status, str(self.command_id)) - # def set_parameter(self, command_ref, parameters): - # dest = np.array(parameters[0]) - # robot_distance_table = {} - # for name, engine in self.engine_clients.items(): - # pos = engine.get_position()[3] - # pos = np.array(pos) - # robot_distance_table[name] = np.linalg.norm(dest - pos) - # nearest_robot = min(robot_distance_table, key=robot_distance_table.get) - # print("Nearest robot is '{}'".format(nearest_robot)) - - # target_engine = self.engine_clients[nearest_robot] - # target_engine.set_parameter(command_ref, parameters) - # status = RoIS_HRI.ReturnCode_t.OK.value - # self.command_id += 1 - # return (status, str(self.command_id)) + def analyze_c_status(self, component, command_id): + while True: + # Is component_event_queue thread-safe ? + msg = self.component_event_queue.get() + (target_pos, robot_name), methodname = xmlrpc.client.loads(msg) + if self.goal_command_table[str(target_pos)] == command_id: + print("Command (id: {}) was completed by {} which reached goal {}."\ + .format(command_id, robot_name, target_pos)) + self.completed(command_id, Component_Status.READY.value) + del self.goal_command_table[str(target_pos)] + return + else: + self.component_event_queue.put(msg) + time.sleep(3) class IF_server: diff --git a/route_guidance_ros/scripts/toplevel_engine_client.py b/route_guidance_ros/scripts/main_engine_client.py similarity index 96% rename from route_guidance_ros/scripts/toplevel_engine_client.py rename to route_guidance_ros/scripts/main_engine_client.py index b522efb77f351816dfc7a2cd1e1bce115edef5de..1e7e3a18b65ac98a06f42a93214b0e1f2aa21ad6 100644 --- a/route_guidance_ros/scripts/toplevel_engine_client.py +++ b/route_guidance_ros/scripts/main_engine_client.py @@ -12,6 +12,7 @@ import xmlrpc.client from pyrois import RoIS_HRI +from pyrois.Service_Application_IF import Service_Application_IF class SystemIF(RoIS_HRI.SystemIF): @@ -117,12 +118,13 @@ class EventIF(RoIS_HRI.EventIF): return (status, results) -class IF(SystemIF, CommandIF, QueryIF, EventIF): +class IF(SystemIF, CommandIF, QueryIF, EventIF, Service_Application_IF): """IF """ def __init__(self, uri): self._uri = uri self._proxy = xmlrpc.client.ServerProxy(self._uri) + if __name__ == "__main__": pass diff --git a/route_guidance_ros/scripts/service_app.py b/route_guidance_ros/scripts/service_app.py new file mode 100644 index 0000000000000000000000000000000000000000..fc0a61466d5292eba2167273a070718442cbce40 --- /dev/null +++ b/route_guidance_ros/scripts/service_app.py @@ -0,0 +1,95 @@ +from main_engine_client import IF as RoIS_IF +from pyrois.Service_Application_IF import Service_Application_IF as pyrois_Service_Application_IF +from pyrois import RoIS_Service, RoIS_HRI + +import logging +import queue +import threading +import time + +import socketserver +import xmlrpc.server + + +class Service_Application_IF(pyrois_Service_Application_IF): + """Service_Application_IF + """ + def __init__(self, uri, logger=None): + self._uri = uri + self._proxy = xmlrpc.client.ServerProxy(self._uri) + self.command_id_table = {} + if logger is not None: + self.logger = logger + self.th = threading.Thread(target=self.event_poll_loop) + self.th.start() + + def event_poll_loop(self): + print("poll loop started") + while True: + # try: + # self.poll_event() + self.poll_event() + # except: + # print("Error ") + # continue + + def poll_event(self): + """poll_event + """ + msg = self._proxy.poll_event() + if msg is None: + return + (params, methodname) = xmlrpc.client.loads(msg) + #self.logger.debug('poll_event: '+methodname) + print("params: ", params, ", methodname: ", methodname) + if methodname == 'completed': + self.completed(params[0], params[1]) + elif methodname == 'notify_error': + self.notify_error(params[0], params[1]) + elif methodname == 'notify_event': + self.notify_event(params[0], params[1], params[2], params[3]) + + def completed(self, command_id, status): + self.command_id_table[command_id] = True + print(self.command_id_table) + + def notify_error(self, error_id, error_type): + print('received error event {}({}) ', + error_id, + RoIS_Service.ErrorType(error_type).name) + + def notify_event(self, event_id, event_type, subscribe_id, expire): + print('received event {} {} {} {}', + event_id, + event_type, + subscribe_id, + expire) + + def go_robot_to(self, dest): + self._proxy = xmlrpc.client.ServerProxy(self._uri) + time.sleep(3) + (return_code, command_id) = self._proxy.set_parameter('Navigation', [dest, "", ""]) + stautus = RoIS_HRI.ReturnCode_t(return_code) + self.command_id_table[command_id] = False + print(self.command_id_table) + + +def example_sa_IF(url, q): + try: + logger = logging.getLogger('Service_Application_IF') + logger.setLevel(logging.DEBUG) + ch = logging.handlers.QueueHandler(q) + # ch = logging.StreamHandler() + ch.setLevel(logging.DEBUG) + formatter = logging.Formatter( + '%(asctime)s - %(name)s - %(levelname)s - %(message)s') + ch.setFormatter(formatter) + logger.addHandler(ch) + a = Service_Application_IF(url, logger=logger) + except KeyboardInterrupt: + print("Interrupted") + + +if __name__ == '__main__': + q = queue.Queue() + example_sa_IF("http://localhost:8000", q) diff --git a/route_guidance_ros/scripts/sub_engine.py b/route_guidance_ros/scripts/sub_engine.py index 638b0f791be9d24bccc341bbe89c717493ea7fd5..6a90c2524324b93a521ef34f169c09d98fe4b920 100644 --- a/route_guidance_ros/scripts/sub_engine.py +++ b/route_guidance_ros/scripts/sub_engine.py @@ -166,15 +166,20 @@ class EventIF(RoIS_HRI.EventIF): return (status, results) +from pyrois.Service_Application_Base_example import Service_Application_Base from Navigation_client import Navigation_Client as NavClient from System_Information_client import System_Information_Client as SysClient +from pyrois.RoIS_Common import Component_Status +import queue +import time -class IF(SystemIF, CommandIF, QueryIF, EventIF, RoIS_Service.Service_Application_Base): +class IF(SystemIF, CommandIF, QueryIF, EventIF, Service_Application_Base): """IF """ def __init__(self, Engine, engine_port): super().__init__(Engine) self.command_id = 0 + self.event_queue = queue.Queue() self.compoent_clients = { 'Navigation': NavClient('http://localhost:' + str(engine_port+1)), 'System_Information': SysClient('http://localhost:' + str(engine_port+2)) @@ -182,12 +187,15 @@ class IF(SystemIF, CommandIF, QueryIF, EventIF, RoIS_Service.Service_Application def set_parameter(self, component_ref, parameters): status = None + self.command_id += 1 if not component_ref in self.compoent_clients: status = RoIS_HRI.ReturnCode_t.ERROR.value else: + print("[set_parameter] component_ref started") target_component_client = self.compoent_clients[component_ref] status = target_component_client.set_parameter(*parameters).value - self.command_id += 1 + th = threading.Thread(target=self.analyze_c_status, daemon=True, args=(target_component_client, str(self.command_id))) + th.start() return (status, str(self.command_id)) ### Remove ### @@ -201,6 +209,16 @@ class IF(SystemIF, CommandIF, QueryIF, EventIF, RoIS_Service.Service_Application return (status.value, timestamp, robot_ref, position_data) ############## + def analyze_c_status(self, component, command_id): + while True: + time.sleep(5) + (_, c_status) = component.component_status() + print("command_id: {}, status: {}".format(command_id, c_status)) + if c_status == Component_Status.READY: + self.completed(command_id, c_status.value) + return + + class IF_server: """IF_Server """ diff --git a/route_guidance_ros/scripts/test_app.py b/route_guidance_ros/scripts/test_app.py new file mode 100644 index 0000000000000000000000000000000000000000..e16f7de0bdfcfa6ed0f34b5420664b0319c4d08b --- /dev/null +++ b/route_guidance_ros/scripts/test_app.py @@ -0,0 +1,23 @@ +# 1. launch multi navigation. +# 2. run this test. + + +from service_app import Service_Application_IF as Service +import time +from pyrois.RoIS_Common import Component_Status +from utilities import setup_multi_robot + +process = setup_multi_robot() + +time.sleep(10) +print("launching Service...") +service = Service('http://localhost:8000') +print("Service was established.") +for dest in [[25, 0], [0, 20], [5, 0]]: + status = service.go_robot_to(dest) + print(status) + time.sleep(5) +# service.all_finished() + +time.sleep(30) +print("finish") diff --git a/route_guidance_ros/scripts/test_toplevel_engine.py b/route_guidance_ros/scripts/test_main_engine.py similarity index 76% rename from route_guidance_ros/scripts/test_toplevel_engine.py rename to route_guidance_ros/scripts/test_main_engine.py index 36e2654a8ce99feeef05041444a37d468ffb471a..c00e159b8c9a0552f54bde03ef1070b2a5a1c0d9 100644 --- a/route_guidance_ros/scripts/test_toplevel_engine.py +++ b/route_guidance_ros/scripts/test_main_engine.py @@ -2,7 +2,7 @@ # 2. run this test. -from toplevel_engine_client import IF as Engine +from main_engine_client import IF as Engine import time from pyrois.RoIS_Common import Component_Status from utilities import setup_multi_robot @@ -10,11 +10,15 @@ from utilities import setup_multi_robot process = setup_multi_robot() engine = Engine('http://127.0.0.1:8000') +print("Engine was established.") +time.sleep(10) engine.connect() for dest in [[25, 0], [0, 20], [5, 0]]: status = engine.set_parameter('Navigation', [dest, "", ""]) print(status) time.sleep(5) +# engine.all_finished() +time.sleep(30) engine.disconnect() print("finish") diff --git a/route_guidance_ros/scripts/test_main_engine_with_service.py b/route_guidance_ros/scripts/test_main_engine_with_service.py new file mode 100644 index 0000000000000000000000000000000000000000..60718ad2c0addde7796fca415b8dae155c8179f9 --- /dev/null +++ b/route_guidance_ros/scripts/test_main_engine_with_service.py @@ -0,0 +1,46 @@ +# 1. launch multi navigation. +# 2. run this test. + + +from main_engine_client import IF as Engine +import time +from pyrois.RoIS_Common import Component_Status +from pyrois.Service_Application_IF import Service_Application_IF +from utilities import setup_multi_robot +import xmlrpc + + +class Service(Service_Application_IF): + def __init__(self, uri="http://localhost:8000"): + super().__init__(uri) + self.current_dest_index = 0 + self.is_running = False + + def completed(self, command_id, status): + print("Service command_id {} was completed.".format(command_id)) + self.current_dest_index += 1 + self.is_running = False + + def go_robot_to(self, dest): + self._proxy = xmlrpc.client.ServerProxy(self._uri) + time.sleep(3) + (return_code, command_id) = self._proxy.set_parameter('Navigation', [dest, "", ""]) + print("go_robot_to {} called with command_id {}".format(dest, command_id)) + self.is_running = True + + def run(self): + destinations = [ + [25, 10], [0, 20], [5, 0], [10, 0], [25, 20], [0, 5] + ] + for dest in destinations: + self.go_robot_to(dest) + while self.is_running: + time.sleep(3) + + +if __name__ == '__main__': + process = setup_multi_robot() + time.sleep(10) + service = Service() + service.run() + print("finish") diff --git a/route_guidance_ros/scripts/test_sub_engine.py b/route_guidance_ros/scripts/test_sub_engine.py index a8724fc6d6706e50753911ba30507a3deb8a5732..c6b6aad0a458b90e3664b8214c9b8a0accaddc28 100644 --- a/route_guidance_ros/scripts/test_sub_engine.py +++ b/route_guidance_ros/scripts/test_sub_engine.py @@ -17,11 +17,11 @@ for dest in destinations: print(engine.set_parameter('Navigation',[dest, "", ""])) navi_status = Component_Status.BUSY while navi_status != Component_Status.READY: - server_status, navi_status = engine.get_navi_status() - print("TEST: status = {}".format(navi_status)) + # server_status, navi_status = engine.get_navi_status() + # print("TEST: status = {}".format(navi_status)) time.sleep(1) - position = engine.get_position() - print("TEST: position = {}".format(position)) + # position = engine.get_position() + # print("TEST: position = {}".format(position)) time.sleep(3) #print(engine.analysis_c_status()) diff --git a/route_guidance_ros/scripts/test_sub_engine_with_service.py b/route_guidance_ros/scripts/test_sub_engine_with_service.py new file mode 100644 index 0000000000000000000000000000000000000000..01f0dc3951f905ae562a4ff5ee7ff3513eeb6bb5 --- /dev/null +++ b/route_guidance_ros/scripts/test_sub_engine_with_service.py @@ -0,0 +1,62 @@ +# 1. launch single navigation. +# 2. run this test. + + +from sub_engine_client import IF as Engine +import time +from pyrois.RoIS_Common import Component_Status +from utilities import setup_single_robot +from collections import namedtuple +from service_app import Service_Application_IF +import xmlrpc + + +class CommandStatus(object): + def __init__(self, is_finished): + self.is_finished = is_finished + + def __repr__(self): + return "CommandStatus\n".format(self.is_finished) + + +class Service(Service_Application_IF): + def __init__(self, uri): + super().__init__(uri) + self.commmand_status_table = {} + self.is_navigation_running = False + + def completed(self, command_id, status): + print(self.commmand_status_table[command_id]) + self.commmand_status_table[command_id].is_finished = True + print("----------------------------------------------") + print("commmand_status:\n", self.commmand_status_table) + print("----------------------------------------------") + self.is_navigation_running = False + + def go_robot_to(self, dest): + self.is_navigation_running = True + self._proxy = xmlrpc.client.ServerProxy(self._uri) + time.sleep(3) + status, command_id = \ + self._proxy.set_parameter('Navigation',[dest, "", ""]) + self.commmand_status_table[command_id] = CommandStatus(False) + print("----------------------------------------------") + print("commmand_status:\n", self.commmand_status_table) + print("----------------------------------------------") + + def run(self): + destinations = [[5, 0], [10, 0], [25, 0], [25, 20]] + for dest in destinations: + self.go_robot_to(dest) + while self.is_navigation_running: + time.sleep(1) + + +process = setup_single_robot() +time.sleep(10) +service = Service('http://127.0.0.1:8010') +time.sleep(10) + +service.run() + +print("finish") diff --git a/route_guidance_ros/scripts/utilities.py b/route_guidance_ros/scripts/utilities.py index 0a3eb2294b52ab10acf39e7a4ff7775c558a2b98..8ff7edbd8686917b336cdb9dcef6de79c8e63e0f 100644 --- a/route_guidance_ros/scripts/utilities.py +++ b/route_guidance_ros/scripts/utilities.py @@ -30,9 +30,9 @@ class SubEngineWrapper(SubprocessWrapper): super().__init__(["python3", "sub_engine.py", str(engine_port)]) -class ToplevelEngineWrapper(SubprocessWrapper): +class MainEngineWrapper(SubprocessWrapper): def __init__(self): - super().__init__(["python3", "toplevel_engine.py"]) + super().__init__(["python3", "main_engine.py"]) def launch_components_and_subengines(**robot_port_table): @@ -57,15 +57,15 @@ def setup_single_robot(): def setup_multi_robot(): process = launch_components_and_subengines(robot1=8010, robot2=8020, robot3=8030) - process.append(ToplevelEngineWrapper()) - print("Toplevel Engine Constructed.") - time.sleep(5) command = [ "rosrun", "route_guidance_ros", "VirtualNavigation.py", "8041", "robot1", "robot2", "robot3" ] process.append(SubprocessWrapper(command)) print("Virtual Navigation Component Constructed.") + time.sleep(5) + process.append(MainEngineWrapper()) + print("Main Engine Constructed.") time.sleep(10) return process