speed_square_wave.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 import rospy
00003 from dataspeed_ulc_can import Speed
00004 
00005 
00006 class SpeedSquareWave(Speed):
00007 
00008     def __init__(self):
00009         rospy.init_node('speed_square_wave')
00010         super(SpeedSquareWave, self).__init__()
00011 
00012     def timer_callback(self, event):
00013         if self.enabled:
00014             if self.v1 == 0 and self.v2 == 0:
00015                 rospy.logwarn_throttle(1.0, 'both speed targets are zero')
00016 
00017             if self.t >= self.period:
00018                 # Reset time when period is reached and switch back to initial speed
00019                 self.t = 0
00020                 self.ulc_cmd.linear_velocity = self.v1
00021             elif self.t >= 0.5 * self.period:
00022                 # During second half of period, switch to other speed
00023                 self.t += 0.02
00024                 self.ulc_cmd.linear_velocity = self.v2
00025             else:
00026                 # During first half of period, use initial speed
00027                 self.t += 0.02
00028                 self.ulc_cmd.linear_velocity = self.v1
00029 
00030             self.pub_ulc_cmd.publish(self.ulc_cmd)
00031 
00032 
00033 if __name__ == '__main__':
00034     try:
00035         node_instance = SpeedSquareWave()
00036         rospy.spin()
00037     except rospy.ROSInterruptException:
00038         pass


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Thu May 16 2019 03:04:21