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 WaypointNavPimp(concert_service_utilities.ResourcePimp):
00032
00033 def setup_variables(self):
00034 '''
00035 Need to setup the following variables
00036 service_priority, service_id, resource_type, available_resource_publisher_name, capture_topic_name
00037 '''
00038 (service_name, service_description, service_priority, service_id) = concert_service_utilities.get_service_info()
00039 self.service_priority = service_priority
00040 self.service_id = service_id
00041 self.resource_type = 'rocon_apps/waypoint_nav'
00042 self.available_resource_publisher_name = 'available_waypoint_nav'
00043 self.capture_topic_name = 'capture_waypoint_nav'
00044
00045
00046 self._default_map_topic = 'map'
00047 self._default_waypoints_topic = 'waypoints'
00048
00049 def ros_capture_callback(self, request_id, msg):
00050 '''
00051 Processes the service pair server 'capture_waypiont_nav'. This will run
00052 in a thread of its own for each request. It has a significantly long lock
00053 though - this needs to get fixed.
00054 '''
00055
00056
00057 response = concert_service_msgs.CaptureResourceResponse()
00058 response.result = False
00059 if not msg.release:
00060 if msg.rocon_uri not in [r.uri for r in self.available_resources]:
00061 self.logwarn("couldn't capture resource [not available][%s]" % msg.rocon_uri)
00062 response.result = False
00063 else:
00064 resource = self._create_resource(msg.rocon_uri)
00065 request_result, resource_request_id = self.send_allocation_request(resource)
00066 response.result = request_result
00067 if request_result == False:
00068 self.logwarn("couldn't capture resource [timed out][%s]" % msg.rocon_uri)
00069 else:
00070 self.loginfo("captured resource [%s][%s]" % (msg.rocon_uri, resource_request_id))
00071 response.remappings = resource.remappings
00072 else:
00073 self.send_releasing_request(msg.rocon_uri)
00074 response.result = True
00075 return response
00076
00077 def _create_resource(self, uri):
00078
00079 resource = scheduler_msgs.Resource()
00080 resource.id = unique_id.toMsg(unique_id.fromRandom())
00081 resource.rapp = self.resource_type
00082 resource.uri = uri
00083 resource.remappings = []
00084 map_remapped, waypoints_remapped = self._get_remapped_topic(rocon_uri.parse(resource.uri).name.string)
00085 resource.remappings = [rocon_std_msgs.Remapping(self._default_map_topic, map_remapped), rocon_std_msgs.Remapping(self._default_waypoints_topic, waypoints_remapped)]
00086 return resource
00087
00088 def _get_remapped_topic(self, name):
00089 '''
00090 Sets up remapping rules for Rapp configuration
00091 '''
00092 map_remapped = rospy.resolve_name(rospy.get_param('map_topic'))
00093 waypoints_remapped = rospy.resolve_name(rospy.get_param('waypoints_topic'))
00094
00095 return map_remapped, waypoints_remapped
00096
00097 def loginfo(self, msg):
00098 rospy.loginfo("WaypointNavPimp : %s"%str(msg))
00099
00100 def logwarn(self, msg):
00101 rospy.logwarn("WaypointNavPimp : %s"%str(msg))
00102
00103 def logerr(self, msg):
00104 rospy.logerr("WaypointNavPimp : %s"%str(msg))
00105
00106
00107
00108
00109
00110 if __name__ == '__main__':
00111 rospy.init_node('waypoint_nav_pimp')
00112
00113 pimp = WaypointNavPimp()
00114 rospy.on_shutdown(pimp.cancel_all_requests)
00115 pimp.loginfo("Initialised")
00116 rospy.spin()
00117 pimp.loginfo("Bye Bye")