class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client= Ros(self._ip,self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) self.br =tf2_ros.StaticTransformBroadcaster() self.t = [] def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my my=rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self,message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ",self._message_type) rospy.loginfo(rospy.get_caller_id() + " Time from previous message %s ",(rospy.get_time()-my)) my=rospy.get_time() for i in range(len(message['transforms'])): self.t.append(TransformStamped()) self.t[-1].header.stamp = rospy.Time.now() self.t[-1].header.frame_id = message['transforms'][i]['header']['frame_id'] self.t[-1].child_frame_id = message['transforms'][i]['child_frame_id'] self.t[-1].transform.translation.x = message['transforms'][i]['transform']['translation']['x'] self.t[-1].transform.translation.y = message['transforms'][i]['transform']['translation']['y'] self.t[-1].transform.translation.z = message['transforms'][i]['transform']['translation']['z'] self.t[-1].transform.rotation.x = message['transforms'][i]['transform']['rotation']['x'] self.t[-1].transform.rotation.y = message['transforms'][i]['transform']['rotation']['y'] self.t[-1].transform.rotation.z = message['transforms'][i]['transform']['rotation']['z'] self.t[-1].transform.rotation.w = message['transforms'][i]['transform']['rotation']['w'] self.br.sendTransform(self.t) def _start_receiving(self): self._listener.subscribe(self._receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
def run_add_two_ints_service(): ros_client = Ros('127.0.0.1', 9090) service = Service(ros_client, '/test_server', 'rospy_tutorials/AddTwoInts') def dispose_server(): service.unadvertise() service.ros.call_later(1, service.ros.terminate) def add_two_ints(request, response): response['sum'] = request['a'] + request['b'] if response['sum'] == 42: service.ros.call_later(2, dispose_server) return True def check_sum(result): assert (result['sum'] == 42) def invoke_service(): client = Service(ros_client, '/test_server', 'rospy_tutorials/AddTwoInts') client.call(ServiceRequest({'a': 2, 'b': 40}), check_sum, print) service.advertise(add_two_ints) ros_client.call_later(1, invoke_service) ros_client.run_event_loop()
def run_param_manipulation(): ros_client = Ros('127.0.0.1', 9090) def delete_param_done(_): ros_client._test_param_del = True def get_param_done(value): ros_client._test_param_value = value delete_param = Param(ros_client, 'test_param') delete_param.delete(delete_param_done) def set_param_done(_): ros_client._test_param_set = True check_param = Param(ros_client, 'test_param') check_param.get(get_param_done) param = Param(ros_client, 'test_param') param.set('test_value', set_param_done) def verify(): assert (ros_client._test_param_set is True) assert (ros_client._test_param_value == 'test_value') assert (ros_client._test_param_del is True) ros_client.terminate() ros_client.call_later(1, verify) ros_client.run_event_loop()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client= Ros(self._ip,self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) self._listener2= Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my my=rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self,message): global my rospy.loginfo(rospy.get_caller_id() + " I heard a message of %s",self._message_type) rospy.loginfo(rospy.get_caller_id() + " Time from previous message %s",(rospy.get_time()-my) )#edw mou leei unicode type my=rospy.get_time() try: msg=Image() msg.header.seq=message['header']['seq'] msg.header.stamp.secs=message['header']['stamp']['secs'] msg.header.stamp.nsecs=message['header']['stamp']['nsecs'] msg.header.frame_id=message['header']['frame_id'] msg.height=message['height'] msg.width=message['width'] msg.encoding=str(message['encoding']) msg.is_bigendian=message['is_bigendian'] msg.step=message['step'] msg.data=message['data'].decode('base64') self._rosPub=rospy.Publisher(self._local_topic_name, Image, queue_size=10) #message type is String instead of msg_stds/String self._rosPub.publish(msg) except: print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type, file): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client = Ros(self._ip, self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine self._service = None self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) self._file = file def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) self._ros_client.send_on_ready(Message(self._file)) global my my = rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self, message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ", self._message_type) rospy.loginfo( rospy.get_caller_id() + " Time from previous message %s ", (rospy.get_time() - my)) my = rospy.get_time() try: msg = Clock() msg.clock.secs = message['clock']['secs'] msg.clock.nsecs = message['clock']['nsecs'] self._rosPub = rospy.Publisher( self._local_topic_name, Clock, queue_size=10 ) #message type is String instead of msg_stds/String self._rosPub.publish(msg) except: print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
def run_rosapi_topics(): ros_client = Ros('127.0.0.1', 9090) def callback(topic_list): assert ('/rosout' in topic_list['topics']) ros_client.terminate() def get_topics(): ros_client.get_topics(callback) ros_client.on_ready(get_topics) ros_client.run_event_loop()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client = Ros(self._ip, self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine # self._2listener = None # Should be specified by the automation engine self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) # self._2listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my # global my2 # my2=rospy.get_time() my = rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self, message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ", self._message_type) rospy.loginfo( rospy.get_caller_id() + " Time from previous message %s ", (rospy.get_time() - my)) my = rospy.get_time() try: msg = Status() msg.header.seq = message['header']['seq'] msg.header.stamp.secs = message['header']['stamp']['secs'] msg.header.stamp.nsecs = message['header']['stamp']['nsecs'] msg.header.frame_id = message['header']['frame_id'] msg.id = message['id'] msg.active = message['active'] msg.heartbeat_timeout = message['heartbeat_timeout'] msg.heartbeat_period = message['heartbeat_period'] msg.instance_id = message['instance_id'] # for i in range(0,8): # msg.orientation_covariance[i]=message['orientation_covariance'][i] # msg.angular_velocity_covariance[i]=message['angular_velocity_covariance'][i] # msg.linear_acceleration_covariance[i]=message['linear_acceleration_covariance'][i] self._rosPub = rospy.Publisher(self._local_topic_name, Status, queue_size=10) self._rosPub.publish(msg) except: print('Error') # def _2receive_message(self,message): # global my2 # rospy.loginfo(rospy.get_caller_id() + "I heard a message %s",(rospy.get_time()-my2)) # my2=rospy.get_time() # try: # msg=Clock() # msg.clock.secs=message['clock']['secs'] # msg.clock.nsecs=message['clock']['nsecs'] # self._rosPub=rospy.Publisher('/test/clock2', Clock, queue_size=10) #message type $ # self._rosPub.publish(msg) # except: # print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) # self._listener2.subscribe(self._2receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client= Ros(self._ip,self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine # self._2listener = None # Should be specified by the automation engine self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) # self._2listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my # global my2 # my2=rospy.get_time() my=rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self,message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ",self._message_type) rospy.loginfo(rospy.get_caller_id() + " Time from previous message %s ",(rospy.get_time()-my)) my=rospy.get_time() try: msg=TFMessage() msg1=TransformStamped() list_msg=[] for i in range(len(message['transforms'])) : msg1.header.seq=message['transforms'][i]['header']['seq'] msg1.header.stamp.secs=message['transforms'][i]['header']['stamp']['secs'] msg1.header.stamp.nsecs=message['transforms'][i]['header']['stamp']['nsecs'] msg1.header.frame_id=message['transforms'][i]['header']['frame_id'] msg1.child_frame_id=message['transforms'][i]['child_frame_id'] msg1.transform.translation.x=message['transforms'][i]['transform']['translation']['x'] msg1.transform.translation.y=message['transforms'][i]['transform']['translation']['y'] msg1.transform.translation.z=message['transforms'][i]['transform']['translation']['z'] msg1.transform.rotation.x=message['transforms'][i]['transform']['rotation']['x'] msg1.transform.rotation.y=message['transforms'][i]['transform']['rotation']['y'] msg1.transform.rotation.z=message['transforms'][i]['transform']['rotation']['z'] msg1.transform.rotation.w=message['transforms'][i]['transform']['rotation']['w'] list_msg.append(msg1) msg=TFMessage(list_msg) self._rosPub=rospy.Publisher(self._local_topic_name, TFMessage, queue_size=10) self._rosPub.publish(msg) except: print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) # self._listener2.subscribe(self._2receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client = Ros(self._ip, self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my my = rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self, message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ", self._message_type) rospy.loginfo( rospy.get_caller_id() + " Time from previous message %s ", (rospy.get_time() - my)) my = rospy.get_time() # try: msg = OccupancyGrid() msg.header.seq = message['header']['seq'] msg.header.stamp = rospy.Time.now( ) #.secs=message['header']['stamp']['secs'] msg.header.frame_id = message['header']['frame_id'] #type unicode msg.info.map_load_time.secs = message['info']['map_load_time']['secs'] msg.info.map_load_time.nsecs = message['info']['map_load_time'][ 'nsecs'] msg.info.resolution = message['info']['resolution'] msg.info.width = message['info']['width'] msg.info.height = message['info']['height'] msg.info.origin.position.x = message['info']['origin']['position']['x'] msg.info.origin.position.y = message['info']['origin']['position']['y'] msg.info.origin.position.z = message['info']['origin']['position']['z'] msg.info.origin.orientation.x = message['info']['origin'][ 'orientation']['x'] msg.info.origin.orientation.y = message['info']['origin'][ 'orientation']['y'] msg.info.origin.orientation.z = message['info']['origin'][ 'orientation']['z'] msg.info.origin.orientation.w = message['info']['origin'][ 'orientation']['w'] msg.data = message['data'] # for i in range(len(message['data'])): # print(i) # msg.data[i]=message['data'][i] self._rosPub = rospy.Publisher(self._local_topic_name, OccupancyGrid, queue_size=10) self._rosPub.publish(msg) # except: # print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
class ROSCloudSubBridge(object): def __init__(self, ip, port, local_topic_name, remote_topic_name, message_type): self._ip = ip self._port = port self._local_topic_name = local_topic_name self._remote_topic_name = remote_topic_name self._message_type = message_type self._ros_client= Ros(self._ip,self._port) self._rosPub = None # Should be specified by the automation engine self._listener = None # Should be specified by the automation engine self._logger = logging.getLogger(self.__class__.__name__) self._logger.setLevel(logging.DEBUG) def _run_topic_pubsub(self): try: self._listener = Topic(self._ros_client, self._remote_topic_name, self._message_type) rospy.init_node('cloudsub', anonymous=True) global my my=rospy.get_time() self._ros_client.on_ready(self._start_receiving, run_in_thread=True) self._ros_client.run_event_loop() except: self._logger.exception("Fatal error in constructor") def _receive_message(self,message): global my rospy.loginfo(rospy.get_caller_id() + " Message type %s ",self._message_type) rospy.loginfo(rospy.get_caller_id() + " Time from previous message %s ",(rospy.get_time()-my)) my=rospy.get_time() try: msg=LaserScan() msg.header.seq=message['header']['seq'] msg.header.stamp.secs=message['header']['stamp']['secs'] msg.header.stamp.nsecs=message['header']['stamp']['nsecs'] msg.header.frame_id=message['header']['frame_id'] msg.angle_min=message['angle_min'] msg.angle_max=message['angle_max'] msg.angle_increment=message['angle_increment'] msg.time_increment=message['time_increment'] msg.scan_time=message['scan_time'] msg.range_min=message['range_min'] msg.range_max=message['range_max'] ranges_list=[] intensities_list=[] for i in range(len(message['ranges'])): ranges_list.append(float) if message['ranges'][i]==None: ranges_list[i]=float('NaN') else: ranges_list[i]=message['ranges'][i] for i in range(len(message['intensities'])): intensities_list.append(float) if message['intensities'][i]==None: intensities_list[i]=float('NaN') else: intensities_list[i]=message['intensities'][i] msg.ranges=ranges_list msg.intensities=intensities_list self._rosPub=rospy.Publisher(self._local_topic_name, LaserScan, queue_size=10) self._rosPub.publish(msg) except: print('Error') def _start_receiving(self): self._listener.subscribe(self._receive_message) def start(self): signal.signal(signal.SIGINT, lambda *x: self.stop()) self._run_topic_pubsub() def stop(self): if self._ros_client is not None: self._ros_client.terminate()
if self.current_topic: self.current_topic.unsubscribe(self._process_tf_array) if __name__ == '__main__': import logging from roslibpy import Ros FORMAT = '%(asctime)-15s [%(levelname)s] %(message)s' logging.basicConfig(level=logging.DEBUG, format=FORMAT) ros_client = Ros('127.0.0.1', 9090) def run_tf_example(): tfclient = TFClient(ros_client, fixed_frame='world', angular_threshold=0.01, translation_threshold=0.01) tfclient.subscribe('turtle2', print) def dispose_server(): tfclient.dispose() ros_client.call_later(10, dispose_server) ros_client.call_later(11, ros_client.close) ros_client.call_later(12, ros_client.terminate) run_tf_example() ros_client.run_event_loop()