get_controller_state.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2015, Fetch Robotics Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #     * Redistributions of source code must retain the above copyright
00010 #       notice, this list of conditions and the following disclaimer.
00011 #     * Redistributions in binary form must reproduce the above copyright
00012 #       notice, this list of conditions and the following disclaimer in the
00013 #       documentation and/or other materials provided with the distribution.
00014 #     * Neither the name of the Fetch Robotics Inc. nor the names of its
00015 #       contributors may be used to endorse or promote products derived from
00016 #       this software without specific prior written permission.
00017 # 
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL FETCH ROBOTICS INC. BE LIABLE FOR ANY
00022 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00023 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00024 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00025 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00026 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00027 # THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 
00029 # Author: Michael Ferguson
00030 
00031 import sys
00032 import rospy
00033 import actionlib
00034 from actionlib_msgs.msg import GoalStatus
00035 from robot_controllers_msgs.msg import QueryControllerStatesAction, \
00036                                        QueryControllerStatesGoal, \
00037                                        ControllerState
00038 
00039 ACTION_NAME = "/query_controller_states"
00040 
00041 if __name__ == "__main__":
00042     rospy.init_node("get_robot_controllers_state")
00043 
00044     rospy.loginfo("Connecting to %s..." % ACTION_NAME)
00045     client = actionlib.SimpleActionClient(ACTION_NAME, QueryControllerStatesAction)
00046     client.wait_for_server()
00047 
00048     rospy.loginfo("Requesting state of controllers...")
00049 
00050     goal = QueryControllerStatesGoal()
00051     client.send_goal(goal)
00052     client.wait_for_result()
00053     if client.get_state() == GoalStatus.SUCCEEDED:
00054         result = client.get_result()
00055         for state in result.state:
00056             if state.state == state.RUNNING:
00057                 print("%s[%s]: RUNNING" % (state.name, state.type))
00058             elif state.state == state.STOPPED:
00059                 print("%s[%s]: STOPPED" % (state.name, state.type))
00060             elif state.state == state.ERROR:
00061                 print("%s[%s]: ERROR!!" % (state.name, state.type))
00062     elif client.get_state() == GoalStatus.ABORTED:
00063         rospy.logerr(client.get_goal_status_text())


robot_controllers_interface
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:50:24