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 ArtVehicle
00017 from art_msgs.msg import SteeringCommand
00018 from art_msgs.msg import SteeringState
00019
00020 max_steer_degrees = ArtVehicle.max_steer_degrees
00021
00022 def log_steering_state(state):
00023 rospy.logdebug("steering angle, sensor: %.3f %.3f (time %.6f)",
00024 state.angle, state.sensor, state.header.stamp.to_sec())
00025
00026 def log_steering_cmd(cmd):
00027 rospy.loginfo("sending steering angle: " + str(cmd.angle))
00028
00029 def test():
00030 topic = rospy.Publisher('steering/cmd', SteeringCommand)
00031 rospy.Subscriber('steering/state', SteeringState, log_steering_state)
00032 rospy.init_node('test_steering')
00033
00034 rospy.loginfo('starting steering test')
00035
00036
00037 cmd = SteeringCommand()
00038 cmd.request = SteeringCommand.Degrees
00039 cmd.angle = 0.0
00040 delta = 5.0
00041
00042 while not rospy.is_shutdown():
00043 if cmd.angle <= -max_steer_degrees or cmd.angle >= max_steer_degrees:
00044 delta = -delta
00045 cmd.angle += delta
00046 log_steering_cmd(cmd)
00047 topic.publish(cmd)
00048 rospy.sleep(1.0)
00049
00050 if __name__ == '__main__':
00051 try:
00052 test()
00053 except rospy.ROSInterruptException: pass
00054
00055 rospy.loginfo('steering test completed')