autotest: fix integer vs float issues for Python3

This commit is contained in:
Peter Barker 2020-01-18 09:10:50 +11:00 committed by Peter Barker
parent e568f74580
commit 91b01a3eb2
2 changed files with 11 additions and 11 deletions

View File

@ -3451,8 +3451,8 @@ class AutoTestCopter(AutoTest):
0, 0,
0, 0,
0, 0,
roi_lat*1e7, int(roi_lat*1e7),
roi_lon*1e7, int(roi_lon*1e7),
roi_alt, roi_alt,
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
) )
@ -3464,8 +3464,8 @@ class AutoTestCopter(AutoTest):
0, 0,
0, 0,
0, 0,
roi_lat*1e7, int(roi_lat*1e7),
roi_lon*1e7, int(roi_lon*1e7),
roi_alt, roi_alt,
frame=mavutil.mavlink.MAV_FRAME_GLOBAL, frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
) )
@ -3504,8 +3504,8 @@ class AutoTestCopter(AutoTest):
) )
self.mav.mav.global_position_int_send( self.mav.mav.global_position_int_send(
0, # time boot ms 0, # time boot ms
roi_lat * 1e7, int(roi_lat * 1e7),
roi_lon * 1e7, int(roi_lon * 1e7),
0 *1000, # mm alt amsl 0 *1000, # mm alt amsl
0 *1000, # relalt mm UP! 0 *1000, # relalt mm UP!
0, # vx 0, # vx
@ -3517,8 +3517,8 @@ class AutoTestCopter(AutoTest):
self.mav.mav.global_position_int_send( self.mav.mav.global_position_int_send(
0, # time boot ms 0, # time boot ms
roi_lat * 1e7, int(roi_lat * 1e7),
roi_lon * 1e7, int(roi_lon * 1e7),
670 *1000, # mm alt amsl 670 *1000, # mm alt amsl
100 *1000, # mm UP! 100 *1000, # mm UP!
0, # vx 0, # vx

View File

@ -4446,9 +4446,9 @@ switch value'''
fft_len = len(messages[0].data["X"]) fft_len = len(messages[0].data["X"])
sum_fft = { sum_fft = {
"X": numpy.zeros(fft_len/2+1), "X": numpy.zeros(int(fft_len/2+1)),
"Y": numpy.zeros(fft_len/2+1), "Y": numpy.zeros(int(fft_len/2+1)),
"Z": numpy.zeros(fft_len/2+1), "Z": numpy.zeros(int(fft_len/2+1)),
} }
sample_rate = 0 sample_rate = 0
counts = 0 counts = 0