Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 import rospy
00022 import rocon_uri
00023 import concert_service_utilities
00024 import unique_id
00025 import rocon_std_msgs.msg as rocon_std_msgs
00026 import scheduler_msgs.msg as scheduler_msgs
00027 import concert_service_msgs.msg as concert_service_msgs
00028
00029 from concert_software_farmer import SoftwareFarmClient, FailedToStartSoftwareException
00030
00031 class ImageStreamPimp(concert_service_utilities.ResourcePimp):
00032
00033 _default_compressed_image_topic = '/image_stream/compressed_image'
00034
00035 def setup_variables(self):
00036 '''
00037 Need to setup the following variables
00038 service_priority, service_id, resource_type, available_resource_publisher_name, capture_topic_name
00039 '''
00040 (service_name, service_description, service_priority, service_id) = concert_service_utilities.get_service_info()
00041 self.service_priority = service_priority
00042 self.service_id = service_id
00043 self.resource_type = 'rocon_apps/image_stream'
00044 self.available_resource_publisher_name = 'available_image_stream'
00045 self.capture_topic_name = 'capture_image_stream'
00046
00047 def ros_capture_callback(self, request_id, msg):
00048 '''
00049 Processes the service pair server 'capture_teleop'. This will run
00050 in a thread of its own for each request. It has a significantly long lock
00051 though - this needs to get fixed.
00052 '''
00053
00054
00055 response = concert_service_msgs.CaptureResourceResponse()
00056 response.result = False
00057 if not msg.release:
00058 if msg.rocon_uri not in [r.uri for r in self.available_resources]:
00059 self.logwarn("couldn't capture teleopable robot [not available][%s]" % msg.rocon_uri)
00060 response.result = False
00061 else:
00062 resource = self._create_resource(msg.rocon_uri)
00063 request_result, resource_request_id = self.send_allocation_request(resource)
00064 response.result = request_result
00065 if request_result == False:
00066 self.logwarn("couldn't capture image streamable client [timed out][%s]" % msg.rocon_uri)
00067 else:
00068 self.loginfo("captured image streamable client [%s][%s]" % (msg.rocon_uri, resource_request_id))
00069 response.remappings = resource.remappings
00070 else:
00071 self.send_releasing_request(msg.rocon_uri)
00072 response.result = True
00073 return response
00074
00075 def _create_resource(self, uri):
00076
00077 resource = scheduler_msgs.Resource()
00078 resource.id = unique_id.toMsg(unique_id.fromRandom())
00079 resource.rapp = self.resource_type
00080 resource.uri = uri
00081 compressed_image_topic_remapped = self._get_remapped_topic(rocon_uri.parse(resource.uri).name.string)
00082 resource.remappings = [rocon_std_msgs.Remapping(self._default_compressed_image_topic, compressed_image_topic_remapped)]
00083 return resource
00084
00085 def _get_remapped_topic(self, name):
00086 '''
00087 Sets up remapping rules for Rapp configuration
00088 '''
00089 compressed_image_topic_remapped = '/' + name + self._default_compressed_image_topic
00090 return compressed_image_topic_remapped
00091
00092 def loginfo(self, msg):
00093 rospy.loginfo("%s : %s"%(rospy.get_name(), str(msg)))
00094
00095 def logwarn(self, msg):
00096 rospy.logwarn("%s : %s"%(rospy.get_name(), str(msg)))
00097
00098 def logerr(self, msg):
00099 rospy.logerr("%s : %s"%(rospy.get_name(), str(msg)))
00100
00101
00102
00103
00104
00105
00106 WEB_VIDEO_SOFTWARE = 'concert_software_common/web_video_server'
00107
00108 def create_web_video_parameters(address, port):
00109 params = []
00110 params.append(rocon_std_msgs.KeyValue('address', str(address)))
00111 params.append(rocon_std_msgs.KeyValue('port', str(port)))
00112 return params
00113
00114 if __name__ == '__main__':
00115 rospy.init_node('image_stream_pimp')
00116 pimp = ImageStreamPimp()
00117
00118 try:
00119 enable_web_video = rospy.get_param('enable_web_video', False)
00120 if enable_web_video:
00121 address = rospy.get_param('web_video_server_address', 'localhost')
00122 port = rospy.get_param('web_video_server_port', 8080)
00123 sfc = SoftwareFarmClient()
00124 parameters = create_web_video_parameters(address, port)
00125 success, namespace, parameters = sfc.allocate(WEB_VIDEO_SOFTWARE, parameters)
00126
00127 if not success:
00128 raise FailedToStartSoftwareException("Failed to allocate software")
00129 pimp.loginfo("Web video server : %s"%parameters)
00130 pimp.loginfo("Done")
00131 rospy.spin()
00132 sfc.deallocate(WEB_VIDEO_SOFTWARE)
00133 else:
00134 pimp.loginfo("Done")
00135 rospy.spin()
00136 except FailedToStartSoftwareException as e:
00137 pimp.logerr("Teleop Pimp : %s"%str(e))
00138
00139 if not rospy.is_shutdown():
00140 pimp.cancel_all_requests()