make_a_map_pimp.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/concert_services/license/LICENSE
00005 #
00006 ##############################################################################
00007 # About
00008 ##############################################################################
00009 
00010 # Simple script to pimp out make a map operations for rocon interactions.
00011 #
00012 # - watch the app manager status and when it has a remote controller,
00013 # - flip a spawn/kill pair across
00014 # - call the spawn api
00015 #  - the turtle herder will flip back some handles then.
00016 
00017 ##############################################################################
00018 # Imports
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 
00030 class MakeAMapPimp(concert_service_utilities.ResourcePimp):
00031 
00032     _default_cmd_vel_topic = '/teleop/cmd_vel'
00033     _default_compressed_image_topic = '/teleop/compressed_image'
00034     _default_map_topic = 'map'
00035     _default_scan_topic = 'scan'
00036 
00037     def setup_variables(self): 
00038         '''
00039             Need to setup the following variables
00040             service_priority, service_id, resource_type, available_resource_publisher_name, capture_topic_name
00041         '''
00042         (service_name, service_description, service_priority, service_id) = concert_service_utilities.get_service_info()
00043         self.service_priority = service_priority
00044         self.service_id = service_id
00045         self.resource_type = 'concert_service_gazebo/make_a_map'
00046         self.available_resource_publisher_name = 'available_make_a_map'
00047         self.capture_topic_name = 'capture_make_a_map'
00048 
00049     def ros_capture_callback(self, request_id, msg):
00050         '''
00051          Processes the service pair server 'capture_teleop'. 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         # Todo : request the scheduler for this resource,
00056         # use self.allocation_timeout to fail gracefully
00057 
00058         response = concert_service_msgs.CaptureResourceResponse()
00059         response.result = False
00060         if not msg.release:  # i.e. we're capturing:
00061             if msg.rocon_uri not in [r.uri for r in self.available_resources]:
00062                 self.logwarn("couldn't capture teleopable robot [not available][%s]" % msg.rocon_uri)
00063                 response.result = False
00064             else:
00065                 resource = self._create_resource(msg.rocon_uri)
00066                 request_result, resource_request_id = self.send_allocation_request(resource)
00067                 response.result = request_result
00068                 if request_result == False:
00069                     self.logwarn("couldn't capture teleopable robot [timed out][%s]" % msg.rocon_uri)
00070                 else:
00071                     self.loginfo("captured teleopable robot [%s][%s]" % (msg.rocon_uri, resource_request_id))
00072                     response.remappings = resource.remappings
00073         else:  # we're releasing
00074             self.send_releasing_request(msg.rocon_uri)
00075             response.result = True
00076         return response
00077 
00078     def _create_resource(self, uri):
00079         # Create a resource to request
00080         resource = scheduler_msgs.Resource()
00081         resource.id = unique_id.toMsg(unique_id.fromRandom())
00082         resource.rapp = self.resource_type
00083         resource.uri = uri
00084         cmd_vel_remapped, compressed_image_topic_remapped, map_remapped, scan_remapped  = self._get_remapped_topic(rocon_uri.parse(resource.uri).name.string)
00085         resource.remappings = [rocon_std_msgs.Remapping(self._default_cmd_vel_topic, cmd_vel_remapped), rocon_std_msgs.Remapping(self._default_compressed_image_topic, compressed_image_topic_remapped), rocon_std_msgs.Remapping(self._default_map_topic, map_remapped), rocon_std_msgs.Remapping(self._default_scan_topic, scan_remapped)]
00086         return resource
00087 
00088     def _get_remapped_topic(self, name):
00089         '''
00090           Sets up remapping rules for Rapp configuration
00091         '''
00092         cmd_vel_remapped = '/' + name + self._default_cmd_vel_topic
00093         compressed_image_topic_remapped = '/' + name + self._default_compressed_image_topic
00094         map_remapped = '/' + name + '/' + self._default_map_topic
00095         scan_remapped = '/' + name + '/' + self._default_scan_topic
00096 
00097         return cmd_vel_remapped, compressed_image_topic_remapped,map_remapped, scan_remapped 
00098 
00099     def loginfo(self, msg):
00100         rospy.loginfo("MakeAMapPimp : %s"%str(msg))
00101 
00102     def logwarn(self, msg):
00103         rospy.logwarn("MakeAMapPimp : %s"%str(msg))
00104 
00105     def logerr(self, msg):
00106         rospy.logerr("MakeAMapPimp : %s"%str(msg))
00107 
00108 
00109 ##############################################################################
00110 # Launch point
00111 ##############################################################################
00112 
00113 if __name__ == '__main__':
00114     rospy.init_node('make_a_map_pimp')
00115     pimp = MakeAMapPimp()
00116     rospy.spin()
00117     if not rospy.is_shutdown():
00118         pimp.cancel_all_requests()


concert_service_make_a_map
Author(s): Jihoon Lee
autogenerated on Tue Oct 7 2014 12:43:24