$search
00001 #!/usr/bin/python 00002 import roslib 00003 roslib.load_manifest('cob_3d_mapping_pipeline_fake') 00004 00005 import rospy 00006 import actionlib 00007 00008 from cob_3d_mapping_msgs.srv import * 00009 from cob_3d_mapping_msgs.msg import * 00010 00011 class MappingPipelineFake: 00012 def __init__(self): 00013 self.running = False 00014 self.server = actionlib.SimpleActionServer('trigger_mapping', TriggerMappingAction, self.trigger_continuous_mapping, False) 00015 self.server.start() 00016 00017 def trigger_continuous_mapping(self, goal): 00018 feedback = TriggerMappingFeedback() 00019 result = TriggerMappingResult() 00020 if self.running and goal.start == False: 00021 feedback.currentStep.data = "stopping" 00022 self.server.publish_feedback(feedback) 00023 self.running = False 00024 rospy.loginfo("Mapping set to stopped") 00025 result.message.data = "Mapping is now stopped" 00026 if not self.running and goal.start: 00027 feedback.currentStep.data = "starting" 00028 self.server.publish_feedback(feedback) 00029 self.running = True 00030 rospy.loginfo("Mapping set to running") 00031 result.message.data = "Mapping is now running" 00032 self.server.set_succeeded(result) 00033 00034 00035 00036 if __name__ == "__main__": 00037 rospy.init_node('3d_mapping_pipeline_fake') 00038 mapping = MappingPipelineFake() 00039 rospy.loginfo("Fake 3d mapping ready.") 00040 rospy.spin() 00041