Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 import time
00032 import math
00033 import random
00034 random.seed()
00035 import roslib
00036 roslib.load_manifest('life_test')
00037 import rospy
00038 from std_msgs.msg import Float64
00039
00040 from sensor_msgs.msg import JointState
00041
00042
00043 STRAIGHT = 0.82 + math.pi / 2
00044 ROTATION_JOINT = 'fl_caster_rotation_joint'
00045 SPEED = 10.0
00046 PERIOD = 15.0
00047 PI = 3.14159
00048
00049 class LastMessage(object):
00050 def __init__(self, topic, msg_type):
00051 self.msg = None
00052 rospy.Subscriber(topic, msg_type, self.callback)
00053
00054 def last(self):
00055 return self.msg
00056
00057 def callback(self, msg):
00058 self.msg = msg
00059
00060 def main():
00061 angle = STRAIGHT
00062 speed = -SPEED
00063 last_time = 0
00064 rospy.init_node('caster_cmder')
00065 last_state = LastMessage('joint_states', JointState)
00066 pub_steer = rospy.Publisher("caster_fl/steer", Float64)
00067 pub_drive = rospy.Publisher("caster_fl/drive", Float64)
00068 pub_steer.publish(Float64(0.0))
00069 pub_drive.publish(Float64(0.0))
00070 my_rate = rospy.Rate(100)
00071
00072 rospy.loginfo("Waiting for a joint_state message...")
00073 while not last_state.msg and not rospy.is_shutdown(): my_rate.sleep()
00074 while not rospy.is_shutdown():
00075 my_rate.sleep()
00076 jnt_states = last_state.last()
00077 rotation_idx = -1
00078 for i, name in enumerate(jnt_states.name):
00079 if name == ROTATION_JOINT:
00080 rotation_idx = i
00081 break
00082 if rotation_idx < 0:
00083 rospy.logwarn("The %s joint was not found in the mechanism state" % ROTATION_JOINT)
00084 continue
00085
00086
00087 angle_diff = angle - jnt_states.position[rotation_idx]
00088 pub_steer.publish(Float64(6.0 * angle_diff))
00089
00090
00091 if abs(angle_diff) < 0.05:
00092 pub_drive.publish(Float64(speed))
00093 else:
00094 pub_drive.publish(Float64(0.0))
00095
00096 if rospy.get_time() - last_time > (PERIOD / 2):
00097 speed *= -1
00098 if(random.random() > 0.25):
00099 rospy.loginfo('Rotating caster')
00100 pub_drive.publish(Float64(speed))
00101 time.sleep(0.75)
00102 speed *= -1
00103 if angle > PI:
00104 angle -= PI
00105 else:
00106 angle += PI
00107 last_time = rospy.get_time()
00108
00109
00110 if __name__ == '__main__':
00111 main()