CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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