motion_demo.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2014-2017, Dataspeed Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without modification,
9 # are permitted provided that the following conditions are met:
10 #
11 # * Redistributions of source code must retain the above copyright notice,
12 # this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above copyright notice,
14 # this list of conditions and the following disclaimer in the documentation
15 # and/or other materials provided with the distribution.
16 # * Neither the name of Dataspeed Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived from this
18 # software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
21 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
22 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 import rospy
32 from geometry_msgs.msg import Twist
33 
34 def timer_callback(event):
35  pub.publish(twist_output)
36 
37 def simple_motion(twist, duration):
38  global twist_output
39 
40  opposite_twist = Twist()
41  opposite_twist.linear.x = -twist.linear.x
42  opposite_twist.linear.y = -twist.linear.y
43  opposite_twist.angular.z = -twist.angular.z
44 
45  if rospy.is_shutdown():
46  return
47 
48  twist_output = twist
49  rospy.sleep(duration)
50  twist_output = zero_twist
51  rospy.sleep(1.0)
52  twist_output = opposite_twist
53  rospy.sleep(duration)
54  twist_output = zero_twist
55  rospy.sleep(1.0)
56 
58  global pub
59  pub = rospy.Publisher('/mobility_base/cmd_vel', Twist, queue_size=1)
60  rospy.init_node('motion_demo');
61 
62  global zero_twist
63  zero_twist = Twist()
64  zero_twist.linear.x = 0
65  zero_twist.linear.y = 0
66  zero_twist.angular.z = 0
67 
68  global twist_output
69  twist_output = Twist()
70 
71  rospy.Timer(rospy.Duration(0.1), timer_callback)
72 
73  speed = 0.2
74  dist = 1 / 3.28
75  vel = Twist()
76 
77  # Rotate
78  vel.linear.x = 0
79  vel.linear.y = 0
80  vel.angular.z = 0.628
81  simple_motion(vel, 10.2)
82 
83  # North
84  vel.linear.x = speed
85  vel.linear.y = 0
86  vel.angular.z = 0
87  simple_motion(vel, dist/speed)
88 
89  # North-East
90  vel.linear.x = 0.707 * speed
91  vel.linear.y = -0.707 * speed
92  vel.angular.z = 0
93  simple_motion(vel, dist/speed)
94 
95  # East
96  vel.linear.x = 0
97  vel.linear.y = -speed
98  vel.angular.z = 0
99  simple_motion(vel, dist/speed)
100 
101  # South-East
102  vel.linear.x = -0.707 * speed
103  vel.linear.y = -0.707 * speed
104  vel.angular.z = 0
105  simple_motion(vel, dist/speed)
106 
107  # South
108  vel.linear.x = -speed
109  vel.linear.y = 0
110  vel.angular.z = 0
111  simple_motion(vel, dist/speed)
112 
113  # South-West
114  vel.linear.x = -0.707 * speed
115  vel.linear.y = 0.707 * speed
116  vel.angular.z = 0
117  simple_motion(vel, dist/speed)
118 
119  # West
120  vel.linear.x = 0
121  vel.linear.y = speed
122  vel.angular.z = 0
123  simple_motion(vel, dist/speed)
124 
125  # North-West
126  vel.linear.x = 0.707 * speed
127  vel.linear.y = 0.707 * speed
128  vel.angular.z = 0
129  simple_motion(vel, dist/speed)
130 
131 if __name__ == '__main__':
132  motion_demo()
def motion_demo()
Definition: motion_demo.py:57
def simple_motion(twist, duration)
Definition: motion_demo.py:37
def timer_callback(event)
Definition: motion_demo.py:34


mobility_base_examples
Author(s): Dataspeed Inc.
autogenerated on Sun Oct 6 2019 03:40:01