forked from OzairHasan/auto_nav
-
Notifications
You must be signed in to change notification settings - Fork 0
/
auto_nav.py
executable file
·190 lines (154 loc) · 5.77 KB
/
auto_nav.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
#!/usr/bin/env python
import rospy
from nav_msgs.msg import Odometry
from nav_msgs.msg import OccupancyGrid
from sensor_msgs.msg import LaserScan
from tf.transformations import euler_from_quaternion
from geometry_msgs.msg import Twist
import math
import cmath
import numpy as np
import time
laser_range = np.array([])
occdata = []
yaw = 0.0
rotate_speed = 0.1
linear_speed = 0.01
stop_distance = 0.25
occ_bins = [-1, 0, 100, 101]
front_angle = 30
front_angles = range(-front_angle,front_angle+1,1)
def get_odom_dir(msg):
global yaw
orientation_quat = msg.pose.pose.orientation
orientation_list = [orientation_quat.x, orientation_quat.y, orientation_quat.z, orientation_quat.w]
(roll, pitch, yaw) = euler_from_quaternion(orientation_list)
def get_laserscan(msg):
global laser_range
# create numpy array
laser_range = np.array([msg.ranges])
def get_occupancy(msg):
global occdata
# create numpy array
occdata = np.array([msg.data])
# compute histogram to identify percent of bins with -1
occ_counts = np.histogram(occdata,occ_bins)
# calculate total number of bins
total_bins = msg.info.width * msg.info.height
# log the info
rospy.loginfo('Unmapped: %i Unoccupied: %i Occupied: %i Total: %i', occ_counts[0][0], occ_counts[0][1], occ_counts[0][2], total_bins)
def rotatebot(rot_angle):
global yaw
# create Twist object
twist = Twist()
# set up Publisher to cmd_vel topic
pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)
# set the update rate to 1 Hz
rate = rospy.Rate(1)
# get current yaw angle
current_yaw = np.copy(yaw)
# log the info
rospy.loginfo(['Current: ' + str(math.degrees(current_yaw))])
# we are going to use complex numbers to avoid problems when the angles go from
# 360 to 0, or from -180 to 180
c_yaw = complex(math.cos(current_yaw),math.sin(current_yaw))
# calculate desired yaw
target_yaw = current_yaw + math.radians(rot_angle)
# convert to complex notation
c_target_yaw = complex(math.cos(target_yaw),math.sin(target_yaw))
rospy.loginfo(['Desired: ' + str(math.degrees(cmath.phase(c_target_yaw)))])
# divide the two complex numbers to get the change in direction
c_change = c_target_yaw / c_yaw
# get the sign of the imaginary component to figure out which way we have to turn
c_change_dir = np.sign(c_change.imag)
# set linear speed to zero so the TurtleBot rotates on the spot
twist.linear.x = 0.0
# set the direction to rotate
twist.angular.z = c_change_dir * rotate_speed
# start rotation
pub.publish(twist)
# we will use the c_dir_diff variable to see if we can stop rotating
c_dir_diff = c_change_dir
# rospy.loginfo(['c_change_dir: ' + str(c_change_dir) + ' c_dir_diff: ' + str(c_dir_diff)])
# if the rotation direction was 1.0, then we will want to stop when the c_dir_diff
# becomes -1.0, and vice versa
while(c_change_dir * c_dir_diff > 0):
# get current yaw angle
current_yaw = np.copy(yaw)
# get the current yaw in complex form
c_yaw = complex(math.cos(current_yaw),math.sin(current_yaw))
rospy.loginfo('While Yaw: %f Target Yaw: %f', math.degrees(current_yaw), math.degrees(target_yaw))
# get difference in angle between current and target
c_change = c_target_yaw / c_yaw
# get the sign to see if we can stop
c_dir_diff = np.sign(c_change.imag)
# rospy.loginfo(['c_change_dir: ' + str(c_change_dir) + ' c_dir_diff: ' + str(c_dir_diff)])
rate.sleep()
rospy.loginfo(['End Yaw: ' + str(math.degrees(current_yaw))])
# set the rotation speed to 0
twist.angular.z = 0.0
# stop the rotation
time.sleep(1)
pub.publish(twist)
def pick_direction():
global laser_range
rospy.loginfo(['In pick_direction'])
# publish to cmd_vel to move TurtleBot
pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)
# stop moving
twist = Twist()
twist.linear.x = 0.0
twist.angular.z = 0.0
time.sleep(1)
pub.publish(twist)
try:
lr2i = np.argmax(laser_range)
except ValueError:
# in case laser_range is empty
lr2i = 0
rospy.loginfo(['Picked direction: ' + str(lr2i)])
# rotate to that direction
rotatebot(float(lr2i))
# start moving
rospy.loginfo(['Start moving'])
twist.linear.x = linear_speed
twist.angular.z = 0.0
# not sure if this is really necessary, but things seem to work more
# reliably with this
time.sleep(1)
pub.publish(twist)
def mover():
global laser_range
rospy.init_node('mover', anonymous=True)
# subscribe to odometry data
rospy.Subscriber('odom', Odometry, get_odom_dir)
# subscribe to LaserScan data
rospy.Subscriber('scan', LaserScan, get_laserscan)
# subscribe to map occupancy data
rospy.Subscriber('map', OccupancyGrid, get_occupancy)
rate = rospy.Rate(5) # 5 Hz
# find direction with the largest distance from the Lidar
# rotate to that direction
# start moving
pick_direction()
while not rospy.is_shutdown():
# check distances in front of TurtleBot
lr2 = laser_range[0,front_angles]
# distances beyond the resolution of the Lidar are returned
# as zero, so we need to exclude those values
lr20 = (lr2!=0).nonzero()
# find values less than stop_distance
lr2i = (lr2[lr20]<float(stop_distance)).nonzero()
# if the list is not empty
if(len(lr2i[0])>0):
rospy.loginfo(['Stop!'])
# find direction with the largest distance from the Lidar
# rotate to that direction
# start moving
pick_direction()
rate.sleep()
if __name__ == '__main__':
try:
mover()
except rospy.ROSInterruptException:
pass