b_control_status.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import roslib
00005 
00006 
00007 class BControl2Status():
00008     def __init__(self, msg):
00009         if msg.axes[8] == 1.0:
00010             self.buttonU1 = True
00011         else:
00012             self.buttonU1 = False
00013         if msg.axes[9] == 1.0:
00014             self.buttonU2 = True
00015         else:
00016             self.buttonU2 = False
00017         if msg.axes[10] == 1.0:
00018             self.buttonU3 = True
00019         else:
00020             self.buttonU3 = False
00021         if msg.axes[11] == 1:
00022             self.buttonU4 = True
00023         else:
00024             self.buttonU4 = False
00025         if msg.axes[12] == 1.0:
00026             self.buttonU5 = True
00027         else:
00028             self.buttonU5 = False
00029         if msg.axes[13] == 1.0:
00030             self.buttonU6 = True
00031         else:
00032             self.buttonU6 = False
00033         if msg.axes[14] == 1.0:
00034             self.buttonU7 = True
00035         else:
00036             self.buttonU7 = False
00037         if msg.axes[15] == 1.0:
00038             self.buttonU8 = True
00039         else:
00040             self.buttonU8 = False
00041 
00042         if msg.axes[16] == 1.0:
00043             self.buttonL1 = True
00044         else:
00045             self.buttonL1 = False
00046         if msg.axes[17] == 1.0:
00047             self.buttonL2 = True
00048         else:
00049             self.buttonL2 = False
00050         if msg.axes[18] == 1.0:
00051             self.buttonL3 = True
00052         else:
00053             self.buttonL3 = False
00054         if msg.axes[19] == 1.0:
00055             self.buttonL4 = True
00056         else:
00057             self.buttonL4 = False
00058         if msg.axes[20] == 1.0:
00059             self.buttonL5 = True
00060         else:
00061             self.buttonL5 = False
00062         if msg.axes[21] == 1.0:
00063             self.buttonL6 = True
00064         else:
00065             self.buttonL6 = False
00066         if msg.axes[22] == 1.0:
00067             self.buttonL7 = True
00068         else:
00069             self.buttonL7 = False
00070         if msg.axes[23] == 1.0:
00071             self.buttonL8 = True
00072         else:
00073             self.buttonL8 = False
00074 
00075         self.slide1 = msg.axes[24]
00076         self.slide2 = msg.axes[25]
00077         self.slide3 = msg.axes[26]
00078         self.slide4 = msg.axes[27]
00079         self.slide5 = msg.axes[28]
00080         self.slide6 = msg.axes[29]
00081         self.slide7 = msg.axes[30]
00082         self.slide8 = msg.axes[31]
00083 
00084         self.rotate1_1 = msg.axes[0]
00085         self.rotate1_2 = msg.axes[1]
00086         self.rotate1_3 = msg.axes[2]
00087         self.rotate1_4 = msg.axes[3]
00088         self.rotate1_5 = msg.axes[4]
00089         self.rotate1_6 = msg.axes[5]
00090         self.rotate1_7 = msg.axes[6]
00091         self.rotate1_8 = msg.axes[7]
00092 
00093         self.rotate2_1 = msg.axes[32]
00094         self.rotate2_2 = msg.axes[33]
00095         self.rotate2_3 = msg.axes[34]
00096         self.rotate2_4 = msg.axes[35]
00097         self.rotate2_5 = msg.axes[36]
00098         self.rotate2_6 = msg.axes[37]
00099         self.rotate2_7 = msg.axes[38]
00100         self.rotate2_8 = msg.axes[39]
00101 
00102         self.rotate3_1 = msg.axes[40]
00103         self.rotate3_2 = msg.axes[41]
00104         self.rotate3_3 = msg.axes[42]
00105         self.rotate3_4 = msg.axes[43]
00106         self.rotate3_5 = msg.axes[44]
00107         self.rotate3_6 = msg.axes[45]
00108         self.rotate3_7 = msg.axes[46]
00109         self.rotate3_8 = msg.axes[47]
00110 
00111         self.rotate4_1 = msg.axes[48]
00112         self.rotate4_2 = msg.axes[49]
00113         self.rotate4_3 = msg.axes[50]
00114         self.rotate4_4 = msg.axes[51]
00115         self.rotate4_5 = msg.axes[52]
00116         self.rotate4_6 = msg.axes[53]
00117         self.rotate4_7 = msg.axes[54]
00118         self.rotate4_8 = msg.axes[55]
00119 
00120 
00121 import pprint
00122 
00123 def joyCB(msg):
00124     status = BControl2Status(msg)
00125     pprint.PrettyPrinter().pprint(status.__dict__)
00126 
00127 
00128 def main():
00129     import roslib
00130     import rospy
00131     from sensor_msgs.msg import Joy
00132 
00133     rospy.sleep(1)
00134     rospy.init_node('b_control_controller')
00135     s = rospy.Subscriber('/b_control/joy', Joy, joyCB)
00136 
00137     rospy.spin()
00138 
00139 if __name__ == '__main__':
00140     main()


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:30