Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/Vicon/vicon_mavlink.py
9803 views
1
#!/usr/bin/env python3
2
3
# flake8: noqa
4
5
'''
6
connect to a vicon and send mavlink vision data on UDP
7
Released under GNU GPL v3 or later
8
'''
9
10
from pyvicon import pyvicon
11
from pymavlink.quaternion import Quaternion
12
13
# force mavlink2 for yaw in GPS_INPUT
14
import os
15
os.environ['MAVLINK20'] = '1'
16
17
from pymavlink import mavutil
18
from pymavlink import mavextra
19
import math
20
import time
21
import sys
22
23
from argparse import ArgumentParser
24
parser = ArgumentParser(description="vicon to mavlink gateway")
25
26
parser.add_argument("--vicon-host", type=str,
27
help="vicon host name or IP", default="vicon")
28
parser.add_argument("--mavlink-dest", type=str, help="mavlink destination", default="udpout:127.0.0.1:14550")
29
parser.add_argument("--origin", type=str, help="origin in lat,lon,alt,yaw", default="-35.363261,149.165230,584,270")
30
parser.add_argument("--debug", type=int, default=0, help="debug level")
31
parser.add_argument("--target-sysid", type=int, default=1, help="target mavlink sysid")
32
parser.add_argument("--source-sysid", type=int, default=255, help="mavlink source sysid")
33
parser.add_argument("--source-component", type=int, default=mavutil.mavlink.MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY, help="mavlink source component")
34
parser.add_argument("--rate", type=float, default=None, help="message rate for GLOBAL_VISION_POSITION_ESTIMATE")
35
parser.add_argument("--gps-rate", type=int, default=5, help="message rate for GPS_INPUT")
36
parser.add_argument("--gps-nsats", type=int, default=16, help="GPS satellite count")
37
parser.add_argument("--gps-only", action='store_true', default=False, help="only send GPS data")
38
parser.add_argument("--send-zero", action='store_true', default=False, help="send zero data")
39
40
args = parser.parse_args()
41
42
# create a mavlink serial instance
43
mav = mavutil.mavlink_connection(args.mavlink_dest,
44
source_system=args.source_sysid,
45
source_component=args.source_component)
46
47
# create vicon connection
48
vicon = pyvicon.PyVicon()
49
50
origin_parts = args.origin.split(',')
51
if len(origin_parts) != 4:
52
print("Origin should be lat,lon,alt,yaw")
53
sys.exit(1)
54
origin = (float(origin_parts[0]), float(origin_parts[1]), float(origin_parts[2]))
55
56
last_origin_send = 0
57
58
def connect_to_vicon(ip):
59
'''connect to a vicon with given ip or hostname'''
60
global vicon
61
print("Opening connection to %s" % ip)
62
vicon.connect(ip)
63
print("Configuring vicon")
64
vicon.set_stream_mode(pyvicon.StreamMode.ClientPull)
65
vicon.enable_marker_data()
66
vicon.enable_segment_data()
67
vicon.enable_unlabeled_marker_data()
68
vicon.enable_device_data()
69
# wait for first subject to appear
70
print("waiting for vehicle...")
71
while True:
72
vicon.get_frame()
73
name = vicon.get_subject_name(0)
74
if name is not None:
75
break
76
print("Connected to subject %s" % name)
77
78
def get_gps_time(tnow):
79
'''return gps_week and gps_week_ms for current time'''
80
leapseconds = 18
81
SEC_PER_WEEK = 7 * 86400
82
MSEC_PER_WEEK = SEC_PER_WEEK * 1000
83
84
epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2) - leapseconds
85
epoch_seconds = int(tnow - epoch)
86
week = int(epoch_seconds) // SEC_PER_WEEK
87
t_ms = int(tnow * 1000) % 1000
88
week_ms = (epoch_seconds % SEC_PER_WEEK) * 1000 + ((t_ms//200) * 200)
89
return week, week_ms
90
91
92
def main_loop():
93
'''loop getting vicon data'''
94
global vicon
95
name = vicon.get_subject_name(0)
96
segname = vicon.get_subject_root_segment_name(name)
97
last_msg_time = time.time()
98
last_gps_pos = None
99
now = time.time()
100
last_origin_send = now
101
now_ms = int(now * 1000)
102
last_gps_send_ms = now_ms
103
last_gps_send = now
104
gps_period_ms = 1000 // args.gps_rate
105
106
while True:
107
if args.send_zero:
108
time.sleep(0.05)
109
else:
110
vicon.get_frame()
111
112
now = time.time()
113
now_ms = int(now * 1000)
114
115
if args.rate is not None:
116
dt = now - last_msg_time
117
if dt < 1.0 / args.rate:
118
continue
119
120
last_msg_time = now
121
122
# get position as ENU mm
123
if args.send_zero:
124
pos_enu = [0.0, 0.0, 0.0]
125
else:
126
pos_enu = vicon.get_segment_global_translation(name, segname)
127
if pos_enu is None:
128
continue
129
130
# convert to NED meters
131
pos_ned = [pos_enu[0]*0.001, pos_enu[1]*0.001, -pos_enu[2]*0.001]
132
133
# get orientation in euler, converting to ArduPilot conventions
134
if args.send_zero:
135
quat = [0.0, 0.0, 0.0, 1.0]
136
else:
137
quat = vicon.get_segment_global_quaternion(name, segname)
138
q = Quaternion([quat[3], quat[0], quat[1], quat[2]])
139
euler = q.euler
140
roll, pitch, yaw = euler[2], euler[1], euler[0]
141
yaw -= math.pi*0.5
142
143
yaw_cd = int(mavextra.wrap_360(math.degrees(yaw)) * 100)
144
if yaw_cd == 0:
145
# the yaw extension to GPS_INPUT uses 0 as no yaw support
146
yaw_cd = 36000
147
148
if args.debug > 0:
149
print("Pose: [%.3f, %.3f, %.3f] [%.2f %.2f %.2f]" % (
150
pos_ned[0], pos_ned[1], pos_ned[2],
151
math.degrees(roll), math.degrees(pitch), math.degrees(yaw)))
152
153
time_us = int(now * 1.0e6)
154
155
if now - last_origin_send > 1 and not args.gps_only:
156
# send a heartbeat msg
157
mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS, mavutil.mavlink.MAV_AUTOPILOT_GENERIC, 0, 0, 0)
158
159
# send origin at 1Hz
160
mav.mav.set_gps_global_origin_send(args.target_sysid,
161
int(origin[0]*1.0e7), int(origin[1]*1.0e7), int(origin[2]*1.0e3),
162
time_us)
163
last_origin_send = now
164
165
if args.gps_rate > 0 and now_ms - last_gps_send_ms > gps_period_ms:
166
'''send GPS data at the specified rate, trying to align on the given period'''
167
if last_gps_pos is None:
168
last_gps_pos = pos_ned
169
gps_lat, gps_lon = mavextra.gps_offset(origin[0], origin[1], pos_ned[1], pos_ned[0])
170
gps_alt = origin[2] - pos_ned[2]
171
172
gps_dt = now - last_gps_send
173
gps_vel = [ (pos_ned[0]-last_gps_pos[0])/gps_dt,
174
(pos_ned[1]-last_gps_pos[1])/gps_dt,
175
(pos_ned[2]-last_gps_pos[2])/gps_dt ]
176
last_gps_pos = pos_ned
177
178
gps_week, gps_week_ms = get_gps_time(now)
179
180
if args.gps_nsats >= 6:
181
fix_type = 3
182
else:
183
fix_type = 1
184
mav.mav.gps_input_send(time_us, 0, 0, gps_week_ms, gps_week, fix_type,
185
int(gps_lat*1.0e7), int(gps_lon*1.0e7), gps_alt,
186
1.0, 1.0,
187
gps_vel[0], gps_vel[1], gps_vel[2],
188
0.2, 1.0, 1.0,
189
args.gps_nsats,
190
yaw_cd)
191
last_gps_send_ms = (now_ms//gps_period_ms) * gps_period_ms
192
last_gps_send = now
193
194
195
# send VISION_POSITION_ESTIMATE
196
if not args.gps_only:
197
# we force mavlink1 to avoid the covariances which seem to make the packets too large
198
# for the mavesp8266 wifi bridge
199
mav.mav.global_vision_position_estimate_send(time_us,
200
pos_ned[0], pos_ned[1], pos_ned[2],
201
roll, pitch, yaw, force_mavlink1=True)
202
203
204
connect_to_vicon("vicon")
205
main_loop()
206
207
208