4 work out total flight time for a mavlink log 6 from __future__
import print_function
11 from argparse
import ArgumentParser
12 parser = ArgumentParser(description=__doc__)
13 parser.add_argument(
"--condition", default=
None, help=
"condition for packets")
14 parser.add_argument(
"--groundspeed", type=float, default=3.0, help=
"groundspeed threshold")
15 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
17 args = parser.parse_args()
19 from pymavlink
import mavutil
24 '''work out flight time for a log file''' 25 print(
"Processing log %s" % filename)
26 mlog = mavutil.mavlink_connection(filename)
37 m = mlog.recv_match(type=[
'GPS',
'GPS_RAW_INT'], condition=args.condition)
40 total_time += time.mktime(t) - start_time
42 print(
"Flight time : %u:%02u" % (
int(total_time)/60,
int(total_time)%60))
43 return (total_time, total_dist)
44 if m.get_type() ==
'GPS_RAW_INT':
45 groundspeed = m.vel*0.01
47 time_usec = m.time_usec
54 t = time.localtime(m._timestamp)
55 if groundspeed > args.groundspeed
and not in_air:
56 print(
"In air at %s (percent %.0f%% groundspeed %.1f)" % (time.asctime(t), mlog.percent, groundspeed))
58 start_time = time.mktime(t)
59 elif groundspeed < args.groundspeed
and in_air:
60 print(
"On ground at %s (percent %.1f%% groundspeed %.1f time=%.1f seconds)" % (
61 time.asctime(t), mlog.percent, groundspeed, time.mktime(t) - start_time))
63 total_time += time.mktime(t) - start_time
65 if last_msg
is None or time_usec > last_time_usec
or time_usec+30e6 < last_time_usec:
66 if last_msg
is not None:
69 last_time_usec = time_usec
70 return (total_time, total_dist)
74 for filename
in args.logs:
75 for f
in glob.glob(filename):
80 print(
"Total time in air: %u:%02u" % (
int(total_time)//60,
int(total_time)%60))
81 print(
"Total distance travelled: %.1f meters" % total_dist)