motion_demo.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2014-2017, Dataspeed Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without modification,
00009 # are permitted provided that the following conditions are met:
00010 # 
00011 #     * Redistributions of source code must retain the above copyright notice,
00012 #       this list of conditions and the following disclaimer.
00013 #     * Redistributions in binary form must reproduce the above copyright notice,
00014 #       this list of conditions and the following disclaimer in the documentation
00015 #       and/or other materials provided with the distribution.
00016 #     * Neither the name of Dataspeed Inc. nor the names of its
00017 #       contributors may be used to endorse or promote products derived from this
00018 #       software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00023 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00024 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00025 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00026 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00028 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00029 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00030 
00031 import rospy
00032 from geometry_msgs.msg import Twist
00033 
00034 def timer_callback(event):
00035   pub.publish(twist_output)
00036 
00037 def simple_motion(twist, duration):
00038   global twist_output
00039 
00040   opposite_twist = Twist()
00041   opposite_twist.linear.x = -twist.linear.x
00042   opposite_twist.linear.y = -twist.linear.y
00043   opposite_twist.angular.z = -twist.angular.z
00044 
00045   if rospy.is_shutdown():
00046     return
00047 
00048   twist_output = twist
00049   rospy.sleep(duration)
00050   twist_output = zero_twist
00051   rospy.sleep(1.0)
00052   twist_output = opposite_twist
00053   rospy.sleep(duration)
00054   twist_output = zero_twist
00055   rospy.sleep(1.0)
00056 
00057 def motion_demo():
00058   global pub
00059   pub = rospy.Publisher('/mobility_base/cmd_vel', Twist, queue_size=1)
00060   rospy.init_node('motion_demo');
00061 
00062   global zero_twist
00063   zero_twist = Twist()
00064   zero_twist.linear.x = 0
00065   zero_twist.linear.y = 0
00066   zero_twist.angular.z = 0
00067 
00068   global twist_output
00069   twist_output = Twist()
00070 
00071   rospy.Timer(rospy.Duration(0.1), timer_callback)
00072 
00073   speed = 0.2
00074   dist = 1 / 3.28
00075   vel = Twist()
00076   
00077   # Rotate
00078   vel.linear.x = 0
00079   vel.linear.y = 0
00080   vel.angular.z = 0.628
00081   simple_motion(vel, 10.2)
00082 
00083   # North
00084   vel.linear.x = speed
00085   vel.linear.y = 0
00086   vel.angular.z = 0
00087   simple_motion(vel, dist/speed)
00088 
00089   # North-East
00090   vel.linear.x = 0.707 * speed
00091   vel.linear.y = -0.707 * speed
00092   vel.angular.z = 0
00093   simple_motion(vel, dist/speed)
00094   
00095   # East
00096   vel.linear.x = 0
00097   vel.linear.y = -speed
00098   vel.angular.z = 0
00099   simple_motion(vel, dist/speed)
00100   
00101   # South-East
00102   vel.linear.x = -0.707 * speed
00103   vel.linear.y = -0.707 * speed
00104   vel.angular.z = 0
00105   simple_motion(vel, dist/speed)
00106 
00107   # South
00108   vel.linear.x = -speed
00109   vel.linear.y = 0
00110   vel.angular.z = 0
00111   simple_motion(vel, dist/speed)
00112 
00113   # South-West
00114   vel.linear.x = -0.707 * speed
00115   vel.linear.y = 0.707 * speed
00116   vel.angular.z = 0
00117   simple_motion(vel, dist/speed)
00118 
00119   # West
00120   vel.linear.x = 0
00121   vel.linear.y = speed
00122   vel.angular.z = 0
00123   simple_motion(vel, dist/speed)
00124 
00125   # North-West
00126   vel.linear.x = 0.707 * speed
00127   vel.linear.y = 0.707 * speed
00128   vel.angular.z = 0
00129   simple_motion(vel, dist/speed)
00130 
00131 if __name__ == '__main__':
00132   motion_demo()


mobility_base_examples
Author(s): Dataspeed Inc.
autogenerated on Thu Jun 6 2019 21:45:34