-
Notifications
You must be signed in to change notification settings - Fork 0
/
velocity_measurment_node
executable file
·277 lines (221 loc) · 11.9 KB
/
velocity_measurment_node
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
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
#!/usr/bin/env python
import rospy
import numpy as np
import scipy.linalg
import cv2
import copy
import of_library as of
import time
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import Image
from sensor_msgs.msg import Imu
from sensor_msgs.msg import Range
from geometry_msgs.msg import Vector3
from geometry_msgs.msg import Quaternion
#x: n,2 array of feature pos
#u: n,2 array of feature flows
#d: proposed distance to plain
#TODO move to of_library
def generate_test_data(x,v,omega,d,n):
flow=np.zeros((len(x),3))
for i in range(len(x)):
flow[i]=np.dot(n,np.append(x[i],1))/d*(v-v[2]*np.append(x[i],1))+np.cross(omega,np.append(x[i],1))-np.cross(omega,np.append(x[i],1))[2]*np.append(x[i],1)
return flow[:,:2]
def solve_lgs(x,u,d,n,omega):
A=np.empty((0,3))
B=np.empty(0)
#better would be to do it in parallel
for i in range(len(x)):
x_hat=np.array([[0,-1,x[i,1]],[1,0,-x[i,0]],[-x[i,1],x[i,0],0]])
b_i = np.dot(x_hat,np.array([u[i,0],u[i,1],0])+np.dot(x_hat,omega))/np.dot(n,np.append(x[i],1)) #append 3rd dim for calculation (faster method ?)
A=np.append(A,x_hat,axis=0)
B=np.append(B,b_i)
try:
return np.linalg.lstsq(A,B*d) #v,R,rank,s
except:
return np.zeros(3), 10000 * np.ones(3*len(x))
def feasible(x,v,omega,T,u,d,n):
v_cross = [np.cross(np.append(x[i,:],1),v+np.cross(omega,T)) for i in range(len(x))]
u_cross = [np.cross(np.append(x[i,:],0),np.append(u[i,:],0)) for i in range(len(x))]
parallelity = [np.dot(v_cr,u_cr)/(np.linalg.norm(v_cr)*np.linalg.norm(u_cr)) if np.linalg.norm(v_cr)*np.linalg.norm(u_cr) != 0
else 1 for v_cr,u_cr in zip(v_cross,u_cross)]
distance = [np.dot(n,np.append(x[i,:],1))*np.linalg.norm(v_cr)/np.linalg.norm(u_cr)/d if np.linalg.norm(u_cr) != 0
else 0 for i,v_cr,u_cr in zip(np.linspace(0,len(v_cr)),v_cr,u_cr)]
class optical_fusion:
def call_dist(self,data):
distance=data.range
#print(distance)
#self.d=np.dot(np.array([0,0,1]),self.normal) #TODO approximation which doesnt use Tranlation between sonar and camera
def call_imu(self,data):
self.ang = np.array([data.angular_velocity.x,data.angular_velocity.y,data.angular_velocity.z])
self.ang_err = np.array([data.angular_velocity_covariance[0],data.angular_velocity_covariance[4],data.angular_velocity_covariance[8]])
q = data.orientation
R = np.array([[1.0-2*(q.y**2+q.z**2),2*(q.x*q.y-q.w*q.z),2*(q.w*q.y+q.x*q.z)],
[2*(q.x*q.y+q.w*q.z),1.0-2*(q.x**2+q.z**2),2*(q.y*q.z-q.w*q.x)],
[2*(q.x*q.z-q.w*q.y),2*(q.w*q.x+q.y*q.z),1.0-2*(q.x**2+q.y**2)]])
self.rotation = R
self.normal = np.dot(R,np.array([0,0,1])) #if camera was tilted: !=1
if self.first_imu_:
self.old_time = float(data.header.stamp.nsecs)/10**9
self.time_zero = data.header.stamp.secs
self.first_imu_ = False
else:
current_time = float(data.header.stamp.secs-self.time_zero)+float(data.header.stamp.nsecs)/10**9
elapsed_time = current_time-self.old_time
if not self.got_vel_ :
self.vel = self.vel+np.dot(R,np.array([data.linear_acceleration.x,data.linear_acceleration.y,data.linear_acceleration.z])-
9.81*self.normal)*elapsed_time
print_test=np.append(self.vel,current_time)
#print(' '.join(map(str,print_test)))
self.old_time = float(current_time)
self.got_ang_vel_ = True
#returns features and flow in px where (0,0) is the top right
def call_optical(self,image_raw):
start=time.time()
#parameters--------------------------------------------------
#rate = rospy.Rate(20) #updaterate in Hz
min_feat = 20 #minimum number of features
max_feat = 100 #maximum number of features
#Parameters for corner Detection
feature_params = dict( qualityLevel = 0.7,
minDistance = 10, #changed from 7
blockSize = 12 ) #changed from 7
# Parameters for lucas kanade optical flow
lk_params = dict( winSize = (15,15), #changed from (15,15)
maxLevel = 3, #changed from 1
criteria = (cv2.TERM_CRITERIA_EPS | cv2.TERM_CRITERIA_COUNT, 20, 0.03)) #changed from 10,0.03
#------------------------------------------------------------------------------
if self.got_picture_==False:
image_start=time.time()
bridge=CvBridge()
image=bridge.compressed_imgmsg_to_cv2(image_raw,'bgr8') #TODO convert straight to b/w
image_gray=cv2.cvtColor(image,cv2.COLOR_BGR2GRAY)
image_stop=time.time()
#print("image_time",image_stop-image_start)
old_pos=self.feat.reshape((len(self.feat),1,2))
old_pos_err=self.feat_err
if self.first == True:
#first_feat =cv2.goodFeaturesToTrack(image_gray,mask=None,maxCorners=max_feat,**feature_params)
#Test data
first_feat = np.array([[-401,300],[399,-300],[400,301],[-400,-299]])
#self.feat_err = 0.01*np.ones((4,2))
self.feat=first_feat.reshape((len(first_feat),2))
self.feat_err=np.zeros(len(first_feat))
else:
'''
pos_start=time.time()
new_pos,status,new_pos_err = cv2.calcOpticalFlowPyrLK(self.old_pic,image_gray,old_pos,None,**lk_params)
self.feat = new_pos[status==1].reshape((len(new_pos[status==1]),2))
self.feat_err = new_pos_err[status==1]
self.flow = new_pos[status==1]-old_pos[status==1]
old_pos_err = old_pos_err.reshape(glen(old_pos_err),1)
#self.flow_err = np.sqrt(new_pos_err[status==1]**2+old_pos_err[status==1]**2)
pos_stop=time.time()
#print("tracking_time",pos_stop-pos_start)
visual_start=time.time()
for i in range(len(old_pos)):
visual_points=cv2.circle(image,(old_pos[i,0,0],old_pos[i,0,1]),10,50,cv2.FILLED)
self.visualize.publish(bridge.cv2_to_imgmsg(visual_points))
visual_stop=time.time()
#print("visualisation_time",visual_stop-visual_start)
'''
self.init = False
self.got_picture_ = True
stop=time.time()
#print("elapsed photo time:",stop-start)
'''
if len(old_pos) <= min_feat:
ft_mask=np.ones_like(image_gray)
for i in range(len(old_pos)):
cv2.circle(ft_mask,(old_pos[i,0,0],old_pos[i,0,1]),30,0,cv2.FILLED)
new_feat_start=time.time()
new_features = cv2.goodFeaturesToTrack(self.old_pic,mask=ft_mask,maxCorners=max_feat-len(old_pos),**feature_params)
new_feat_stop=time.time()
try:
self.feat = np.append(self.feat,new_features.reshape(len(new_features),2),axis=0)
#self.feat_err = np.append(self.feat_err,np.zeros([len(new_featuers),2]),axis=0)
except:
self.feat=self.feat
#print("no new features found")
print("new feature time",new_feat_stop-new_feat_start)
'''
self.old_pic=image_gray
self.first=False
#rate.sleep()
def __init__(self):
#TODO init values in numpy, not true data type
scaling = 0.01 #needs to be calibrated
self.vel = np.array([0.1,0.1,0.1]) #trans vel.
self.vel_err = np.array([0.1,0.1,0.1]) #trans vel.
self.feat = np.ones((1,2)) #array of features
self.feat_err = np.ones((1,1))
self.flow = np.zeros((1,1,2)) #array of flows
self.flow_err = np.zeros((1,1,2))
self.ang = np.array([0,0,0])
self.ang_err = np.zeros((3,3))
self.d = 0.75 #distance in m
self.d_err = 0
self.rotation = np.array([[1,0,0],[0,1,0],[0,0,1]])
self.old_pic = np.zeros((480,640)) # last picture for calculating OF
self.old_time = 0 #dummy value for first time
self.time_zero = 0
self.offset = np.array([0,0,0.1])
self.normal = np.array([0,0,1])
self.normal_err = np.array([0,0,1])
#flags
self.init = True
self.first = True
self.first_imu_ = True
self.got_normal_ = False
self.got_vel_ = False
self.got_picture_= False
self.got_ang_vel_= False
rospy.Subscriber('/mavros/imu/data', Imu, self.call_imu)
rospy.Subscriber('/camerav2_1280x960/image_raw/compressed', CompressedImage,self.call_optical)
rospy.Subscriber('/mavros/distance_sensor/hrlv_ez4_pub',Range,self.call_dist)
self.visualize=rospy.Publisher('visualisation',Image,queue_size=1)
while not rospy.is_shutdown():
#implement flag handling and publishing at certain times
if self.got_picture_ and not self.init:
start=time.time()
#zero picture coordinates before solving lgs
translation=of.pix_trans((320,240))
x=copy.deepcopy(self.feat)
x=x.astype(float)
x[:,0]=(x[:,0]-translation[0])*scaling
x[:,1]=(x[:,1]-translation[1])*scaling
u=self.flow.reshape(len(self.flow),2)*scaling #copy flow
u=generate_test_data(x,np.array([1,1,1]),np.array([0,0,0]),self.d,np.array([0,0,1]))
feasibility,dummy_d = of.r_tilde(x,u,self.normal,self.vel,self.d) #TODO distance calc. faulty
#print(feasibility)
feasibility= -1*np.ones(len(x)) #hardcoded to one to test while system stationary
T = 0.0 #feasibility Treshold
x = x[feasibility <= T]
u = u[feasibility <= T]
dummy_d = dummy_d[feasibility<=T]
self.feat = self.feat[feasibility <= T]
#feasible(self.feat,self.vel,self.ang,self.offset,u,self.d,self.normal)
if len(x) >= 3:
#statistical analysis and d calculation
d_sorted=np.sort(dummy_d)
d_diff=[j-i for i, j in zip(d_sorted[:-1],d_sorted[1:])]
#splits=d_diff>=d_exp_err
if len(x) >=3:
v_obs,R,rank,s = solve_lgs(x,u,self.d,self.normal,self.ang)
v_uav = np.dot(self.rotation,v_obs-np.dot(np.array([[0,-self.ang[2],self.ang[1]],[self.ang[2],0,-self.ang[0]],[-self.ang[1],self.ang[0],0]]),self.offset))
print(' '.join(map(str,v_obs)))
got_vel_ = True
self.vel = v_uav
got_vel_ = False
#print("Residuum:",np.sqrt(R/len(x)))
stop=time.time()
#print("elapsed velocity calculation time:",stop-start)
self.got_picture_=False
if __name__=='__main__':
print('++')
rospy.init_node('velocity_calc')
print('--')
try:
node=optical_fusion()
except rospy.ROSInterruptException: pass