00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 import roslib;
00013 roslib.load_manifest('art_servo')
00014
00015 import rospy
00016 from art_msgs.msg import Shifter
00017
00018 def log_shifter_state(state):
00019 rospy.logdebug("shifter gear: %u, relays: %02x (time %.6f)",
00020 state.gear, state.relays, state.header.stamp.to_sec())
00021
00022 def log_shifter_cmd(cmd):
00023
00024 rospy.loginfo("sending shifter command: " + str(cmd.gear))
00025
00026 def test():
00027 topic = rospy.Publisher('shifter/cmd', Shifter)
00028 rospy.Subscriber('shifter/state', Shifter, log_shifter_state)
00029 rospy.init_node('test_shifter')
00030
00031 rospy.loginfo('starting shifter test')
00032
00033
00034 cmd = Shifter()
00035 cmd.gear = Shifter.Park
00036 reset_cmd = Shifter()
00037 reset_cmd.gear = Shifter.Reset
00038
00039 while not rospy.is_shutdown():
00040 if cmd.gear > Shifter.Drive:
00041 cmd.gear = Shifter.Park
00042
00043
00044 topic.publish(cmd)
00045 log_shifter_cmd(cmd)
00046 cmd.gear += 1
00047 rospy.sleep(1.0)
00048
00049
00050 topic.publish(reset_cmd)
00051 log_shifter_cmd(reset_cmd)
00052 rospy.sleep(1.0)
00053
00054 if __name__ == '__main__':
00055 try:
00056 test()
00057 except rospy.ROSInterruptException: pass
00058
00059 rospy.loginfo('shifter test completed')