closechuck.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 """
00004    Copyright 2013 Southwest Research Institute
00005  
00006    Licensed under the Apache License, Version 2.0 (the "License");
00007    you may not use this file except in compliance with the License.
00008    You may obtain a copy of the License at
00009  
00010      http://www.apache.org/licenses/LICENSE-2.0
00011  
00012    Unless required by applicable law or agreed to in writing, software
00013    distributed under the License is distributed on an "AS IS" BASIS,
00014    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015    See the License for the specific language governing permissions and
00016    limitations under the License.
00017    """
00018 
00019 import roslib; roslib.load_manifest('mtconnect_msgs')
00020 import rospy
00021 
00022 # Brings in the SimpleActionClient
00023 import actionlib
00024 
00025 # Brings in the messages used by the material_load action.
00026 import mtconnect_msgs.msg
00027 
00028 def close_chuck_client():
00029     rospy.loginfo('Launched CloseChuck Action CLient')
00030     # Creates the SimpleActionClient, passing the type of the action
00031     # (CloseChuckAction) to the constructor.
00032     client = actionlib.SimpleActionClient('CloseChuckClient', mtconnect_msgs.msg.CloseChuckAction)
00033     
00034     # Waits until the action server has started up and started listening for goals.
00035     rospy.loginfo('Waiting for Generic Action Server')
00036     client.wait_for_server()
00037     rospy.loginfo('Generic Action Server Activated')
00038 
00039     # Creates a DoorAcknowledge goal to send to the action server.
00040     goal = mtconnect_msgs.msg.CloseChuckGoal()
00041     goal.close_chuck = 'CLOSED'
00042     
00043     # Sends the goal to the action server.
00044     rospy.loginfo('Sending the goal')
00045     client.send_goal(goal)
00046     
00047     # Waits for the server to finish performing the action.
00048     rospy.loginfo('Waiting for result')
00049     client.wait_for_result()
00050     
00051     # Obtain result
00052     result = client.get_result() # result must be a string
00053     rospy.loginfo('Returning the result --> %s' % result)
00054     return
00055 
00056 if __name__ == '__main__':
00057     try:
00058         # Initializes a rospy node so that the SimpleActionClient can
00059         # publish and subscribe over ROS.
00060         rospy.init_node('CloseChuckActionClient')
00061         result = close_chuck_client()
00062         rospy.loginfo('Action Result --> %s' % result)
00063     except rospy.ROSInterruptException:
00064         print 'program interrupted before completion'
00065 


mtconnect_ros_bridge
Author(s): Stephen L. Wiedmann
autogenerated on Mon Jan 6 2014 11:30:45