Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/Vicon/vicon_mavlink.py
Views: 1798
#!/usr/bin/env python31'''2connect to a vicon and send mavlink vision data on UDP3Released under GNU GPL v3 or later4'''56from pyvicon import pyvicon7from pymavlink.quaternion import Quaternion89# force mavlink2 for yaw in GPS_INPUT10import os11os.environ['MAVLINK20'] = '1'1213from pymavlink import mavutil14from pymavlink import mavextra15import math16import time17import sys1819from argparse import ArgumentParser20parser = ArgumentParser(description="vicon to mavlink gateway")2122parser.add_argument("--vicon-host", type=str,23help="vicon host name or IP", default="vicon")24parser.add_argument("--mavlink-dest", type=str, help="mavlink destination", default="udpout:127.0.0.1:14550")25parser.add_argument("--origin", type=str, help="origin in lat,lon,alt,yaw", default="-35.363261,149.165230,584,270")26parser.add_argument("--debug", type=int, default=0, help="debug level")27parser.add_argument("--target-sysid", type=int, default=1, help="target mavlink sysid")28parser.add_argument("--source-sysid", type=int, default=255, help="mavlink source sysid")29parser.add_argument("--source-component", type=int, default=mavutil.mavlink.MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY, help="mavlink source component")30parser.add_argument("--rate", type=float, default=None, help="message rate for GLOBAL_VISION_POSITION_ESTIMATE")31parser.add_argument("--gps-rate", type=int, default=5, help="message rate for GPS_INPUT")32parser.add_argument("--gps-nsats", type=int, default=16, help="GPS satellite count")33parser.add_argument("--gps-only", action='store_true', default=False, help="only send GPS data")34parser.add_argument("--send-zero", action='store_true', default=False, help="send zero data")3536args = parser.parse_args()3738# create a mavlink serial instance39mav = mavutil.mavlink_connection(args.mavlink_dest,40source_system=args.source_sysid,41source_component=args.source_component)4243# create vicon connection44vicon = pyvicon.PyVicon()4546origin_parts = args.origin.split(',')47if len(origin_parts) != 4:48print("Origin should be lat,lon,alt,yaw")49sys.exit(1)50origin = (float(origin_parts[0]), float(origin_parts[1]), float(origin_parts[2]))5152last_origin_send = 05354def connect_to_vicon(ip):55'''connect to a vicon with given ip or hostname'''56global vicon57print("Opening connection to %s" % ip)58vicon.connect(ip)59print("Configuring vicon")60vicon.set_stream_mode(pyvicon.StreamMode.ClientPull)61vicon.enable_marker_data()62vicon.enable_segment_data()63vicon.enable_unlabeled_marker_data()64vicon.enable_device_data()65# wait for first subject to appear66print("waiting for vehicle...")67while True:68vicon.get_frame()69name = vicon.get_subject_name(0)70if name is not None:71break72print("Connected to subject %s" % name)7374def get_gps_time(tnow):75'''return gps_week and gps_week_ms for current time'''76leapseconds = 1877SEC_PER_WEEK = 7 * 8640078MSEC_PER_WEEK = SEC_PER_WEEK * 10007980epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2) - leapseconds81epoch_seconds = int(tnow - epoch)82week = int(epoch_seconds) // SEC_PER_WEEK83t_ms = int(tnow * 1000) % 100084week_ms = (epoch_seconds % SEC_PER_WEEK) * 1000 + ((t_ms//200) * 200)85return week, week_ms868788def main_loop():89'''loop getting vicon data'''90global vicon91name = vicon.get_subject_name(0)92segname = vicon.get_subject_root_segment_name(name)93last_msg_time = time.time()94last_gps_pos = None95now = time.time()96last_origin_send = now97now_ms = int(now * 1000)98last_gps_send_ms = now_ms99last_gps_send = now100gps_period_ms = 1000 // args.gps_rate101102while True:103if args.send_zero:104time.sleep(0.05)105else:106vicon.get_frame()107108now = time.time()109now_ms = int(now * 1000)110111if args.rate is not None:112dt = now - last_msg_time113if dt < 1.0 / args.rate:114continue115116last_msg_time = now117118# get position as ENU mm119if args.send_zero:120pos_enu = [0.0, 0.0, 0.0]121else:122pos_enu = vicon.get_segment_global_translation(name, segname)123if pos_enu is None:124continue125126# convert to NED meters127pos_ned = [pos_enu[0]*0.001, pos_enu[1]*0.001, -pos_enu[2]*0.001]128129# get orientation in euler, converting to ArduPilot conventions130if args.send_zero:131quat = [0.0, 0.0, 0.0, 1.0]132else:133quat = vicon.get_segment_global_quaternion(name, segname)134q = Quaternion([quat[3], quat[0], quat[1], quat[2]])135euler = q.euler136roll, pitch, yaw = euler[2], euler[1], euler[0]137yaw -= math.pi*0.5138139yaw_cd = int(mavextra.wrap_360(math.degrees(yaw)) * 100)140if yaw_cd == 0:141# the yaw extension to GPS_INPUT uses 0 as no yaw support142yaw_cd = 36000143144if args.debug > 0:145print("Pose: [%.3f, %.3f, %.3f] [%.2f %.2f %.2f]" % (146pos_ned[0], pos_ned[1], pos_ned[2],147math.degrees(roll), math.degrees(pitch), math.degrees(yaw)))148149time_us = int(now * 1.0e6)150151if now - last_origin_send > 1 and not args.gps_only:152# send a heartbeat msg153mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS, mavutil.mavlink.MAV_AUTOPILOT_GENERIC, 0, 0, 0)154155# send origin at 1Hz156mav.mav.set_gps_global_origin_send(args.target_sysid,157int(origin[0]*1.0e7), int(origin[1]*1.0e7), int(origin[2]*1.0e3),158time_us)159last_origin_send = now160161if args.gps_rate > 0 and now_ms - last_gps_send_ms > gps_period_ms:162'''send GPS data at the specified rate, trying to align on the given period'''163if last_gps_pos is None:164last_gps_pos = pos_ned165gps_lat, gps_lon = mavextra.gps_offset(origin[0], origin[1], pos_ned[1], pos_ned[0])166gps_alt = origin[2] - pos_ned[2]167168gps_dt = now - last_gps_send169gps_vel = [ (pos_ned[0]-last_gps_pos[0])/gps_dt,170(pos_ned[1]-last_gps_pos[1])/gps_dt,171(pos_ned[2]-last_gps_pos[2])/gps_dt ]172last_gps_pos = pos_ned173174gps_week, gps_week_ms = get_gps_time(now)175176if args.gps_nsats >= 6:177fix_type = 3178else:179fix_type = 1180mav.mav.gps_input_send(time_us, 0, 0, gps_week_ms, gps_week, fix_type,181int(gps_lat*1.0e7), int(gps_lon*1.0e7), gps_alt,1821.0, 1.0,183gps_vel[0], gps_vel[1], gps_vel[2],1840.2, 1.0, 1.0,185args.gps_nsats,186yaw_cd)187last_gps_send_ms = (now_ms//gps_period_ms) * gps_period_ms188last_gps_send = now189190191# send VISION_POSITION_ESTIMATE192if not args.gps_only:193# we force mavlink1 to avoid the covariances which seem to make the packets too large194# for the mavesp8266 wifi bridge195mav.mav.global_vision_position_estimate_send(time_us,196pos_ned[0], pos_ned[1], pos_ned[2],197roll, pitch, yaw, force_mavlink1=True)198199200connect_to_vicon("vicon")201main_loop()202203204205