-
Notifications
You must be signed in to change notification settings - Fork 0
/
main_car.py
245 lines (175 loc) · 7.54 KB
/
main_car.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
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
import rospy
import time
import numpy as np
from sshkeyboard import listen_keyboard, stop_listening
from auxiliary.parse_settings import parse_settings
from algorithms.ManeuverAutomaton import ManeuverAutomaton
from algorithms.MPC_Linear import MPC_Linear
from algorithms.GapFollower import GapFollower
from algorithms.DisparityExtender import DisparityExtender
from algorithms.PurePersuit import PurePersuit
from localization.ParticleFilter import ParticleFilter
from sensor_msgs.msg import LaserScan
from ackermann_msgs.msg import AckermannDriveStamped
from nav_msgs.msg import Odometry
from geometry_msgs.msg import PoseStamped
from std_msgs.msg import Float32MultiArray, Bool
CONTROLLER = 'PurePersuit'
RACETRACK = 'ICRA'
OBSERVER = 'ParticleFilter'
x0 = np.array([0, 0, -3.14])
def car_parameter():
"""parameter for the car"""
param = {}
param['mu'] = 1.0489
param['C_Sf'] = 4.718
param['C_Sr'] = 5.4562
param['lf'] = 0.15875
param['lr'] = 0.17145
param['h'] = 0.074
param['m'] = 3.74
param['I'] = 0.04712
# steering constraints
param['s_min'] = -0.4189 # minimum steering angle [rad]
param['s_max'] = 0.4189 # maximum steering angle [rad]
param['sv_min'] = -3.2 # minimum steering velocity [rad / s]
param['sv_max'] = 3.2 # maximum steering velocity [rad / s]
# longitudinal constraints
param['v_min'] = -5.0 # minimum velocity [m / s]
param['v_max'] = 20.0 # maximum velocity [m / s]
param['v_switch'] = 7.319 # switching velocity [m / s]
param['a_max'] = 9.51 # maximum absolute acceleration [m / s ^ 2]
# size of the car
param['width'] = 0.31
param['length'] = 0.58
param['lidar'] = 0.1
return param
class PublisherSubscriber:
"""wrapper class that handles writing control commands and reading sensor measurements"""
def __init__(self, controller):
"""class constructor"""
# publisher
self.pub = rospy.Publisher("/vesc/low_level/ackermann_cmd_mux/input/teleop", AckermannDriveStamped,
queue_size=1)
# subscribers
self.sub_lidar = rospy.Subscriber("/scan", LaserScan, self.callback_lidar)
self.sub_velocity = rospy.Subscriber("/vesc/odom/", Odometry, self.callback_velocity)
self.sub_observer = rospy.Subscriber("observer", Float32MultiArray, self.callback_observer)
self.sub_keyboard = rospy.Subscriber("keyboard", Bool, self.callback_keyboard)
# store motion planner and observer
self.controller = controller
# initialize control input and auxiliary variables
self.u = np.array([0.0, 0.0])
self.run = False
self.x = x0[0]
self.y = x0[1]
self.theta = x0[2]
# wait until first measurement is obtained
rate = rospy.Rate(1000)
while not hasattr(self, 'lidar_data') or not hasattr(self, 'velocity'):
rate.sleep()
# start timers for control command publishing and re-planning
self.timer1 = rospy.Timer(rospy.Duration(0.001), self.callback_timer1)
self.timer2 = rospy.Timer(rospy.Duration(0.01), self.callback_timer2)
rospy.spin()
def callback_lidar(self, msg):
"""store lidar data"""
self.lidar_data = np.asarray(msg.ranges)[0:1080]
def callback_velocity(self, msg):
"""calculate absolute velocity from x- any y-components"""
self.velocity = np.sqrt(msg.twist.twist.linear.x**2 + msg.twist.twist.linear.y**2)
def callback_observer(self, msg):
"""store the current pose estimates"""
self.x = msg.data[0]
self.y = msg.data[1]
self.theta = msg.data[2]
def callback_keyboard(self, msg):
"""store the current keyboard commands"""
self.run = msg.data
def callback_timer1(self, timer):
"""publish the current control commands"""
msg = AckermannDriveStamped()
if self.run and np.mean(self.lidar_data[500:580]) > 0.2:
msg.drive.speed = self.u[0]
msg.drive.steering_angle = self.u[1]
else:
msg.drive.speed = 0.0
msg.drive.steering_angle = 0.0
self.pub.publish(msg)
def callback_timer2(self, timer):
"""obtain new control commands from the controller"""
self.u = self.controller.plan(self.x, self.y, self.theta, self.velocity, self.lidar_data)
class Observer:
def __init__(self, observer):
"""class constructor"""
# publisher
self.pub = rospy.Publisher("observer", Float32MultiArray, queue_size=1, latch=True)
# subscribers
self.sub_lidar = rospy.Subscriber("/scan", LaserScan, self.callback_lidar)
self.sub_velocity = rospy.Subscriber("/vesc/odom/", Odometry, self.callback_velocity)
self.sub_control = rospy.Subscriber("/vesc/low_level/ackermann_cmd_mux/input/teleop", AckermannDriveStamped, self.callback_commands)
# store observer
self.observer = observer
# initialize control input and auxiliary variables
self.u = np.array([0.0, 0.0])
self.x = observer.state[0][0]
self.y = observer.state[0][1]
self.theta = observer.state[0][4]
# wait until first measurement is obtained
rate = rospy.Rate(1000)
while not hasattr(self, 'lidar_data') or not hasattr(self, 'velocity'):
rate.sleep()
# start timers for control command publishing and re-planning
self.timer = rospy.Timer(rospy.Duration(0.01), self.callback_timer)
rospy.spin()
def callback_lidar(self, msg):
"""store lidar data"""
self.lidar_data = np.asarray(msg.ranges)[0:1080]
def callback_velocity(self, msg):
"""calculate absolute velocity from x- any y-components"""
self.velocity = np.sqrt(msg.twist.twist.linear.x**2 + msg.twist.twist.linear.y**2)
def callback_commands(self, msg):
"""store current control commands"""
self.u = np.array([msg.drive.speed, msg.drive.steering_angle])
def callback_timer(self, timer):
"""update pose estimate"""
self.x, self.y, self.theta = self.observer.localize(self.lidar_data, self.velocity, self.u[1], self.u[0])
msg = Float32MultiArray()
msg.data = [self.x, self.y, self.theta]
self.pub.publish(msg)
class Keyboard:
def __init__(self):
"""class constructor"""
# publisher
self.pub = rospy.Publisher("keyboard", Bool, queue_size=1, latch=True)
# function to be exectured on shutdown
rospy.on_shutdown(stop_listening)
# start keyboard listener
self.run = False
listen_keyboard(on_press=self.key_press)
def key_press(self, key):
"""detect keyboard commands"""
if key == "s":
self.run = True
elif key == "e":
self.run = False
msg = Bool()
msg.data = self.run
self.pub.publish(msg)
def start_controller():
# initialize the motion planner
params = car_parameter()
settings = parse_settings(CONTROLLER, RACETRACK, False)
exec('controller = ' + CONTROLLER + '(params, settings)')
# start control cycle
PublisherSubscriber(locals()['controller'])
def start_observer():
# initialize the observer
params = car_parameter()
settings = parse_settings(OBSERVER, RACETRACK, False)
exec('observer = ' + OBSERVER + '(params, settings, x0[0], x0[1], x0[2])')
# start control cycle
Observer(locals()['observer'])
def start_keyboard():
# start keyboard listener
Keyboard()