forked from 3drobotics/FWLoad
-
Notifications
You must be signed in to change notification settings - Fork 0
/
factoryload.py
executable file
·180 lines (152 loc) · 5.53 KB
/
factoryload.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
#!/usr/bin/env python
'''
run factory load, calibration and test
'''
from config import *
import configcheck
import logger
import accelcal
import jtag
import power_control
import time
import util
import sys, os, fcntl
import logger
import colour_text
import connection
import rotate
import barcode
import savedstate
fh = open(os.path.realpath(__file__), 'r')
try:
fcntl.flock(fh, fcntl.LOCK_EX|fcntl.LOCK_NB)
except:
print("another instance of this script is already running. exiting...")
sys.exit(0)
# disable stdout buffering
sys.stdout = os.fdopen(sys.stdout.fileno(), 'w', 0)
from argparse import ArgumentParser
parser = ArgumentParser(description=__doc__)
parser.add_argument("--test", default=False, action='store_true', help="run in test loop")
parser.add_argument("--once", default=False, action='store_true', help="run one install only")
parser.add_argument("--nofw", default=False, action='store_true', help="don't reload firmware")
parser.add_argument("--erase", default=False, action='store_true', help="erase firmware and parameters")
parser.add_argument("--monitor", default=None, help="monitor address")
parser.add_argument("--barcode", default=None, help="override barcode")
args = parser.parse_args()
if args.monitor:
REMOTE_MONITOR['ref'] = args.monitor + ":16550"
REMOTE_MONITOR['test'] = args.monitor + ":16551"
colour_text.print_blue("Starting up")
def factory_install(device_barcode):
'''main factory installer'''
start_time = time.time()
if not args.test:
colour_text.clear_screen()
# start a new log directory on each run
logger.new_log_dir()
logger.reopen_logfile()
logdir = logger.get_log_dir()
logger.info("Logging to %s" % logdir)
logger.info("Device barcode %s" % device_barcode)
colour_text.print_blue('''
==================================================
| Starting installation. Barcode is %s
==================================================
''' % device_barcode)
logger.info(time.ctime())
if args.erase:
if not jtag.erase_firmwares():
colour_text.print_fail('''
======================================
| FAILED: JTAG firmware erase failed
======================================
''')
logger.critical("JTAG firmware erase failed")
return False
if not args.nofw and not jtag.load_all_firmwares(retries=3):
colour_text.print_fail('''
======================================
| FAILED: JTAG firmware install failed
======================================
''')
logger.critical("JTAG firmware install failed")
try:
conn = connection.Connection(ref_only=True)
rotate.center_servos(conn)
except Exception as ex:
print("Failed to center servos: %s" % ex)
pass
return False
if args.erase:
if not connection.erase_parameters():
colour_text.print_fail('''
==========================================
| FAILED: Failed to erase parameters
==========================================
''')
logger.critical("Failed to erase parameters")
return False
if not accelcal.accel_calibrate_retries(retries=4):
colour_text.print_fail('''
==========================================
| FAILED: Accelerometer calibration failed
==========================================
''')
logger.critical("Accelerometer calibration failed")
return False
# all OK
colour_text.print_green('''
================================================
| Device: %s
| PASSED: Factory install complete (%u seconds)
================================================
''' % (device_barcode, (time.time() - start_time)))
logger.info("Factory install complete (%u seconds)" % (time.time() - start_time))
return True
# load the jig state file
savedstate.init()
savedstate.reset('current_cycles')
while True:
logger.get_ftdi()
jigstate = savedstate.get()
logger.info("jigstate: total_cycles = %i" % jigstate['total_cycles'])
logger.info("jigstate: current_cycles = %i" % jigstate['current_cycles'])
util.kill_processes(['mavproxy.py', GDB])
if args.test:
# power cycle each time, simulating new board put in
power_control.power_cycle()
else:
# wait for the power to be switched off, disable serial logging
logger.info("waiting for power off")
util.wait_no_device([FMU_JTAG, IO_JTAG], timeout=600)
device_barcode = args.barcode
if not args.test and device_barcode is None:
colour_text.print_blue('''
==========================================
| PLEASE SWIPE DEVICE BARCODE
==========================================
''')
device_barcode = barcode.barcode_read()
if device_barcode is None:
colour_text.print_fail('''
==========================================
| FAILED: Barcode not detected
==========================================
''')
logger.critical("Barcode not detected")
time.sleep(2)
continue
# we don't use logger for the barcode here as we are still on the previous
# boards log
print("Got barcode: %s" % device_barcode)
logger.info("Barcode detected")
# wait for the power to come on again
while not util.wait_devices([FMU_JTAG, IO_JTAG, FMU_DEBUG]):
logger.info("waiting for power up....")
ret = factory_install(device_barcode)
# increment the cycles counters
savedstate.incr('current_cycles')
savedstate.incr('total_cycles')
if args.once:
sys.exit(int(not ret))