mock_hand.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # ####################################################################
00004 # Copyright (c) 2013 Shadow Robot Company Ltd.
00005 # All rights reserved.
00006 # This program is free software: you can redistribute it and/or modify it
00007 # under the terms of the GNU General Public License as published by the Free
00008 # Software Foundation, either version 2 of the License, or (at your option)
00009 # any later version.
00010 #
00011 # This program is distributed in the hope that it will be useful, but WITHOUT
00012 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00013 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00014 # more details.
00015 #
00016 # You should have received a copy of the GNU General Public License along
00017 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 # ####################################################################
00019 
00020 import rospy
00021 from controller_manager_msgs.srv import ListControllers, ListControllersResponse
00022 from controller_manager_msgs.msg import ControllerState
00023 
00024 class MockHand(object):
00025     """
00026     A ros node to look enough like a shadowhand for these tests.
00027 
00028     List controller service so it looks like a ethercat hand to HandCommander.
00029     """
00030 
00031     def __init__(self, ):
00032         """
00033         @brief Construct a new MockHand, setting up ros connections.
00034         """
00035         self.list_srv = rospy.Service('controller_manager/list_controllers',
00036                 ListControllers, self.list_controllers_cb)
00037         rospy.loginfo("Started MockHand")
00038 
00039     def list_controllers_cb(self, req):
00040         cons = ('sh_ffj0_position_controller',
00041                 'sh_ffj3_position_controller',
00042                 'sh_ffj4_position_controller',
00043                 'sh_lfj0_position_controller',
00044                 'sh_lfj3_position_controller',
00045                 'sh_lfj4_position_controller',
00046                 'sh_lfj5_position_controller',
00047                 'sh_mfj0_position_controller',
00048                 'sh_mfj3_position_controller',
00049                 'sh_mfj4_position_controller',
00050                 'sh_rfj0_position_controller',
00051                 'sh_rfj3_position_controller',
00052                 'sh_rfj4_position_controller',
00053                 'sh_thj1_position_controller',
00054                 'sh_thj2_position_controller',
00055                 'sh_thj3_position_controller',
00056                 'sh_thj4_position_controller',
00057                 'sh_thj5_position_controller',
00058                 'sh_wrj1_position_controller',
00059                 'sh_wrj2_position_controller')
00060         res = ListControllersResponse()
00061         res.controller = [ControllerState(name=c, state='running') for c in cons]
00062         return res
00063 
00064 
00065 if __name__ == "__main__":
00066     try:
00067         rospy.init_node("mock_hand")
00068         node = MockHand()
00069         rospy.spin();
00070     except rospy.ROSInterruptException:
00071         pass
00072 


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:24:55