本文最后更新于 2026-01-21,文章内容可能已经过时。

MP地面站可以分析各项数据,但不能回溯飞行三维轨迹,遂开发此网页。(数据分析有待丰富)

环境:Debian,Python虚拟环境
测试地址:55555

核心功能亮点:

  1. 自适应解析:自动读取 FMT 行,动态锁定 GPS 数据列,兼容不同飞控固件。

  2. 核心算法:实现了你要求的“速度阈值过滤”、“碎片去除”以及“前后20点平滑延伸”逻辑。

  3. 无 Key 实景地图:前端使用墨卡托投影算法,自动计算并加载 Esri World Imagery (ArcGIS) 的免费卫星切片,无需申请 API Key。

  4. 交互可视化:集成 Three.js (3D 轨迹) 与 ECharts (数据图表),并实现二者的数据联动。

1. 后端应用 (Python/Flask)

app.py此文件包含核心数据解析与过滤算法。

import os
import csv
import math
import json
from flask import Flask, render_template, request, jsonify
from pymavlink import mavutil

app = Flask(__name__, template_folder='.')

UPLOAD_FOLDER = 'uploads'
os.makedirs(UPLOAD_FOLDER, exist_ok=True)
ALLOWED_EXTENSIONS = {'log', 'txt', 'csv', 'bin'}

# --- 核心算法参数 ---
SPEED_THRESHOLD_KMH = 5.0 # 稍微降低阈值以捕捉起飞阶段
MIN_CONTINUOUS_POINTS = 10
EXTENSION_POINTS = 20

def allowed_file(filename):
    return '.' in filename and filename.rsplit('.', 1)[1].lower() in ALLOWED_EXTENSIONS

def haversine_distance(lat1, lon1, lat2, lon2):
    R = 6371000
    phi1 = math.radians(lat1)
    phi2 = math.radians(lat2)
    delta_phi = math.radians(lat2 - lat1)
    delta_lambda = math.radians(lon2 - lon1)
    a = math.sin(delta_phi / 2)**2 + math.cos(phi1) * math.cos(phi2) * math.sin(delta_lambda / 2)**2
    c = 2 * math.atan2(math.sqrt(a), math.sqrt(1 - a))
    return R * c

def parse_bin_log(filepath):
    """使用 pymavlink 解析二进制 .bin 文件"""
    raw_gps = []
    raw_bat = []
    raw_att = []
    
    try:
        # 创建 mavlink 连接读取文件
        master = mavutil.mavlink_connection(filepath)
        
        while True:
            # 抓取特定类型的消息
            msg = master.recv_match(type=['GPS', 'BAT', 'ATT'], blocking=False)
            if msg is None:
                break
            
            msg_type = msg.get_type()
            
            if msg_type == 'GPS':
                # 过滤无效定位 (Status < 3 通常意味着没有 3D Fix)
                if hasattr(msg, 'Status') and msg.Status < 3:
                    continue
                    
                # 提取数据
                # 注意: Bin 文件中 Lat/Lng 通常是 int32 (deg * 1e7)
                lat = msg.Lat / 1e7 if abs(msg.Lat) > 1000 else msg.Lat
                lng = msg.Lng / 1e7 if abs(msg.Lng) > 1000 else msg.Lng
                
                raw_gps.append({
                    'time': msg.TimeUS,
                    'lat': lat,
                    'lng': lng,
                    'alt': msg.Alt,
                    'spd': msg.Spd * 3.6 # m/s -> km/h
                })

            elif msg_type == 'BAT':
                raw_bat.append({
                    'time': msg.TimeUS,
                    'volt': msg.Volt,
                    'curr': msg.Curr,
                    'curr_tot': msg.CurrTot
                })
                
            elif msg_type == 'ATT':
                raw_att.append({
                    'time': msg.TimeUS,
                    'roll': msg.Roll,
                    'pitch': msg.Pitch,
                    'yaw': msg.Yaw
                })

    except Exception as e:
        print(f"Error parsing bin file: {e}")
        return None, None, None

    return raw_gps, raw_bat, raw_att

def parse_text_log(filepath):
    """解析文本 .log/.txt 文件 (原逻辑)"""
    raw_gps = []
    raw_bat = []
    raw_att = []
    
    formats = {}
    keys_map = {
        'GPS': {'lat': ['Lat'], 'lng': ['Lng', 'Lon'], 'alt': ['Alt'], 'spd': ['Spd', 'Speed'], 'time': ['TimeUS']},
        'BAT': {'volt': ['Volt'], 'curr': ['Curr'], 'curr_tot': ['CurrTot', 'EnrgTot'], 'time': ['TimeUS']},
        'ATT': {'roll': ['Roll'], 'pitch': ['Pitch'], 'yaw': ['Yaw'], 'time': ['TimeUS']}
    }
    
    try:
        with open(filepath, 'r', encoding='utf-8', errors='ignore') as f:
            reader = csv.reader(f, delimiter=',')
            for row in reader:
                if not row: continue
                msg_type = row[0].strip()

                if msg_type == 'FMT':
                    try:
                        target_name = row[3].strip()
                        columns = [c.strip() for c in row[5:]]
                        formats[target_name] = {name: idx for idx, name in enumerate(columns)}
                    except: pass
                    continue

                if msg_type in keys_map and msg_type in formats:
                    fmt = formats[msg_type]
                    data_map = keys_map[msg_type]
                    
                    try:
                        def get_val(key_list):
                            idx = next((fmt[k] for k in key_list if k in fmt), None)
                            return float(row[1 + idx]) if idx is not None else 0.0

                        time_us = get_val(data_map['time'])

                        if msg_type == 'GPS':
                            lat = get_val(data_map['lat'])
                            lng = get_val(data_map['lng'])
                            if abs(lat) > 1000: lat /= 1e7
                            if abs(lng) > 1000: lng /= 1e7
                            
                            raw_gps.append({
                                'time': time_us,
                                'lat': lat, 'lng': lng,
                                'alt': get_val(data_map['alt']),
                                'spd': get_val(data_map['spd']) * 3.6
                            })
                        elif msg_type == 'BAT':
                            raw_bat.append({
                                'time': time_us,
                                'volt': get_val(data_map['volt']),
                                'curr': get_val(data_map['curr']),
                                'curr_tot': get_val(data_map['curr_tot'])
                            })
                        elif msg_type == 'ATT':
                            raw_att.append({
                                'time': time_us,
                                'roll': get_val(data_map['roll']),
                                'pitch': get_val(data_map['pitch']),
                                'yaw': get_val(data_map['yaw'])
                            })
                    except: continue
    except Exception as e:
        print(f"Error parsing text log: {e}")
        return None, None, None

    return raw_gps, raw_bat, raw_att

def align_and_process(raw_gps, raw_bat, raw_att):
    """数据对齐与融合 (Sample and Hold)"""
    if not raw_gps: return []

    raw_gps.sort(key=lambda x: x['time'])
    raw_bat.sort(key=lambda x: x['time'])
    raw_att.sort(key=lambda x: x['time'])

    aligned_data = []
    bat_idx = 0
    att_idx = 0
    
    for i, gps in enumerate(raw_gps):
        # 推进 BAT 指针
        while bat_idx < len(raw_bat) - 1 and raw_bat[bat_idx+1]['time'] <= gps['time']:
            bat_idx += 1
        # 推进 ATT 指针
        while att_idx < len(raw_att) - 1 and raw_att[att_idx+1]['time'] <= gps['time']:
            att_idx += 1
            
        point = gps.copy()
        point['index'] = i
        
        if raw_bat:
            point['volt'] = raw_bat[bat_idx]['volt']
            point['curr'] = raw_bat[bat_idx]['curr']
            point['mah'] = raw_bat[bat_idx]['curr_tot']
        else:
            point['volt'] = 0; point['curr'] = 0; point['mah'] = 0

        if raw_att:
            point['roll'] = raw_att[att_idx]['roll']
            point['pitch'] = raw_att[att_idx]['pitch']
            point['yaw'] = raw_att[att_idx]['yaw']
        else:
            point['roll'] = 0; point['pitch'] = 0; point['yaw'] = 0

        aligned_data.append(point)
    
    return aligned_data

def calculate_stats(data):
    if not data: return {}
    
    min_alt = min(p['alt'] for p in data)
    max_alt = max(p['alt'] for p in data)
    min_spd = min(p['spd'] for p in data)
    max_spd = max(p['spd'] for p in data)
    
    total_dist = 0
    total_climb = 0
    
    for i in range(1, len(data)):
        d = haversine_distance(data[i-1]['lat'], data[i-1]['lng'], data[i]['lat'], data[i]['lng'])
        total_dist += d
        alt_diff = data[i]['alt'] - data[i-1]['alt']
        if alt_diff > 0: total_climb += alt_diff

    start_volt = data[0]['volt']
    end_volt = data[-1]['volt']
    start_mah = data[0]['mah']
    end_mah = data[-1]['mah']
    consumed_mah = max(0, end_mah - start_mah)
    
    dist_km = total_dist / 1000.0
    mah_per_km = (consumed_mah / dist_km) if dist_km > 0.1 else 0

    return {
        'min_alt': round(min_alt, 1), 'max_alt': round(max_alt, 1),
        'min_spd': round(min_spd, 1), 'max_spd': round(max_spd, 1),
        'total_dist_m': round(total_dist, 0),
        'total_climb_m': round(total_climb, 1),
        'start_volt': round(start_volt, 2),
        'end_volt': round(end_volt, 2),
        'consumed_mah': round(consumed_mah, 0),
        'efficiency': round(mah_per_km, 1)
    }

def filter_trajectory(aligned_data):
    if not aligned_data: return []
    
    n = len(aligned_data)
    valid_mask = [False] * n
    for i in range(n):
        if aligned_data[i]['spd'] >= SPEED_THRESHOLD_KMH:
            valid_mask[i] = True

    segments = []
    current_segment = []
    for i in range(n):
        if valid_mask[i]:
            current_segment.append(i)
        else:
            if current_segment:
                segments.append(current_segment)
                current_segment = []
    if current_segment: segments.append(current_segment)

    final_indices = set()
    for seg in segments:
        if len(seg) < MIN_CONTINUOUS_POINTS: continue
        start_idx = seg[0]
        end_idx = seg[-1]
        extended_start = max(0, start_idx - EXTENSION_POINTS)
        extended_end = min(n - 1, end_idx + EXTENSION_POINTS)
        for i in range(extended_start, extended_end + 1):
            final_indices.add(i)

    processed_data = []
    sorted_indices = sorted(list(final_indices))
    for idx in sorted_indices:
        processed_data.append(aligned_data[idx])
        
    return processed_data

@app.route('/')
def index():
    return render_template('index.html')

@app.route('/upload', methods=['POST'])
def upload_file():
    if 'file' not in request.files: return jsonify({'error': 'No file'}), 400
    file = request.files['file']
    if file.filename == '' or not allowed_file(file.filename): return jsonify({'error': 'Invalid file'}), 400
    
    # 保存文件以便读取
    filepath = os.path.join(UPLOAD_FOLDER, file.filename)
    file.save(filepath)

    try:
        ext = file.filename.rsplit('.', 1)[1].lower()
        
        if ext == 'bin':
            raw_gps, raw_bat, raw_att = parse_bin_log(filepath)
        else:
            raw_gps, raw_bat, raw_att = parse_text_log(filepath)
        
        if not raw_gps:
            return jsonify({'error': 'Failed to parse GPS data or data is empty'}), 400

        aligned_data = align_and_process(raw_gps, raw_bat, raw_att)
        filtered_data = filter_trajectory(aligned_data)
        
        if not filtered_data:
             return jsonify({'error': 'No valid flight trajectory found (check speed threshold)'}), 400

        stats = calculate_stats(filtered_data)
        
        center = {'lat': 0, 'lng': 0}
        if filtered_data:
            center['lat'] = filtered_data[0]['lat']
            center['lng'] = filtered_data[0]['lng']

        return jsonify({
            'message': 'Success',
            'center': center,
            'stats': stats,
            'data': filtered_data
        })
    finally:
        # 清理上传的文件
        if os.path.exists(filepath):
            os.remove(filepath)

if __name__ == '__main__':
    app.run(host='0.0.0.0', port=5555, debug=False)

2. 前端界面 (HTML/JS/Three.js)

index.html此文件包含所有 UI、3D 渲染逻辑、地图瓦片计算和图表展示。

<!DOCTYPE html>
<html lang="zh-CN">
<head>
    <meta charset="UTF-8">
    <meta name="viewport" content="width=device-width, initial-scale=1.0">
    <title>3D 轨迹分析 Pro</title>
    <style>
        body { margin: 0; padding: 0; font-family: 'Segoe UI', sans-serif; overflow: hidden; background: #1a1a1a; color: #eee; }
        
        /* 通用面板样式 */
        .panel { pointer-events: auto; background: rgba(20, 20, 20, 0.9); backdrop-filter: blur(5px); border: 1px solid #444; border-radius: 8px; padding: 15px; position: absolute; box-shadow: 0 4px 12px rgba(0,0,0,0.6); }
        
        /* UI 层 */
        #ui-layer { position: absolute; width: 100%; height: 100%; pointer-events: none; z-index: 10; }
        
        /* 1. 左上:上传面板 */
        #control-panel { top: 15px; left: 15px; width: 280px; z-index: 20; }
        
        /* 2. 左侧:统计信息 */
        #stats-panel { top: 220px; left: 15px; width: 280px; font-size: 0.9rem; z-index: 19; }
        .stat-row { display: flex; justify-content: space-between; margin-bottom: 6px; border-bottom: 1px solid #333; padding-bottom: 2px; }
        .stat-val { color: #4db8ff; font-weight: bold; }

        /* 3. 右上:设置面板 */
        #settings-panel { top: 15px; right: 15px; width: 240px; z-index: 20; }
        .setting-item { margin-bottom: 12px; }
        .setting-item label { display: block; margin-bottom: 6px; font-size: 0.85rem; color: #aaa; }
        input[type="range"] { width: 100%; cursor: pointer; }

        /* 4. 右侧:姿态显示 (新增) */
        #attitude-panel { 
            top: 280px; /* 位于设置面板下方 */
            right: 15px; 
            width: 240px; 
            height: 200px;
            z-index: 20; 
            display: flex;
            flex-direction: column;
            align-items: center;
        }
        #attitude-container {
            width: 100%;
            height: 160px;
            /* 移除背景天际线,改为透明或深色以融合面板 */
            background: rgba(0, 0, 0, 0.3); 
            border-radius: 4px;
            border: 1px solid #555;
        }
        .attitude-label { font-size: 0.8rem; margin-top: 5px; color: #aaa; width: 100%; text-align: center; }

        /* 5. 顶部:播放控制 (新增) */
        #playback-controls {
            top: 15px;
            left: 50%;
            transform: translateX(-50%);
            width: 500px;
            z-index: 30;
            display: flex;
            flex-direction: column;
            align-items: center;
            gap: 8px;
        }
        .pb-row { display: flex; align-items: center; gap: 15px; width: 100%; justify-content: center; }
        .pb-btn {
            background: #333; color: #fff; border: 1px solid #555; 
            width: 40px; height: 32px; border-radius: 4px; cursor: pointer;
            display: flex; align-items: center; justify-content: center; font-size: 1.2rem;
            transition: 0.2s;
        }
        .pb-btn:hover { background: #4db8ff; color: #000; border-color: #4db8ff; }
        .pb-btn.active { background: #4db8ff; color: #000; }
        
        /* 进度条样式 */
        #progress-bar { width: 100%; cursor: pointer; accent-color: #4db8ff; }
        
        /* 底部左侧:图表控制 */
        #chart-controls { 
            position: absolute; 
            bottom: 36vh; left: 15px; z-index: 20; 
            pointer-events: auto; background: rgba(0,0,0,0.8); 
            padding: 8px 15px; border-radius: 6px; border: 1px solid #444;
            display: flex; gap: 15px; font-size: 0.85rem; align-items: center; flex-wrap: wrap; max-width: 80%;
        }
        #chart-controls label { cursor: pointer; display: flex; align-items: center; gap: 4px; user-select: none; }
        
        /* 3D 和 图表区域 */
        #three-container { width: 100vw; height: 65vh; display: block; }
        #chart-container { width: 100vw; height: 35vh; background: #222; border-top: 2px solid #444; position: relative; z-index: 5; }

        /* 交互提示框 */
        #tooltip {
            position: absolute; display: none; background: rgba(0, 0, 0, 0.9); border: 1px solid #4db8ff;
            padding: 10px; border-radius: 4px; font-size: 0.85rem; pointer-events: none; z-index: 100;
            box-shadow: 0 0 10px rgba(77, 184, 255, 0.4); white-space: nowrap;
        }

        h2 { margin: 0 0 12px 0; font-size: 1.1rem; color: #fff; border-left: 4px solid #4db8ff; padding-left: 10px; }
        button { background: #4db8ff; color: #000; border: none; padding: 8px 12px; cursor: pointer; border-radius: 4px; font-weight: bold; width: 100%; margin-top: 5px; transition: 0.2s; }
        button:hover { background: #3aa8ee; }
        input[type="file"] { display: none; }
        .upload-btn { display: block; text-align: center; background: #333; padding: 10px; border-radius: 4px; cursor: pointer; border: 1px dashed #666; color: #aaa; transition: 0.2s; }
        .upload-btn:hover { border-color: #4db8ff; color: #fff; background: #3a3a3a; }
        input[type="checkbox"] { accent-color: #4db8ff; }
    </style>
    
    <script src="https://cdnjs.cloudflare.com/ajax/libs/three.js/r128/three.min.js"></script>
    <script src="https://cdn.jsdelivr.net/npm/[email protected]/examples/js/controls/OrbitControls.js"></script>
    <script src="https://cdnjs.cloudflare.com/ajax/libs/echarts/5.4.3/echarts.min.js"></script>
</head>
<body>

    <div id="ui-layer">
        <!-- 顶部:播放控制 (新增) -->
        <div id="playback-controls" class="panel">
            <div class="pb-row">
                <div class="pb-btn" onclick="stopPlayback()" title="停止">⏹</div>
                <div class="pb-btn" id="btn-play" onclick="togglePlayback()" title="播放/暂停">▶</div>
                <div style="font-size:0.8rem; color:#aaa;">倍速:</div>
                <input type="range" id="speed-slider" min="1" max="50" value="5" style="width:100px;">
                <span id="speed-val" style="font-size:0.8rem; width:30px;">5x</span>
            </div>
            <div class="pb-row">
                <input type="range" id="progress-bar" min="0" value="0" step="1" oninput="scrubPlayback(this.value)">
            </div>
            <div id="playback-time" style="font-size:0.8rem; color:#4db8ff;">00:00:00</div>
        </div>

        <!-- 上传面板 -->
        <div id="control-panel" class="panel">
            <h2>轨迹文件上传</h2>
            <label class="upload-btn">
                点击选择 .log/.bin 文件
                <input type="file" id="fileInput" accept=".log,.txt,.csv,.bin">
            </label>
            <div id="fileName" style="text-align:center; font-size:0.8rem; margin:8px 0; color:#888;">未选择文件</div>
            <button onclick="uploadLog()">开始分析与渲染</button>
            <div id="loadingMsg" style="color:#ffd700; text-align:center; margin-top:5px; display:none;">处理中...</div>
        </div>

        <!-- 统计面板 -->
        <div id="stats-panel" class="panel" style="display:none;">
            <h2>飞行数据总结</h2>
            <div id="stats-content"></div>
        </div>

        <!-- 设置面板 -->
        <div id="settings-panel" class="panel">
            <h2>显示设置</h2>
            <div class="setting-item">
                <label>点大小 (Pixel): <span id="val-size">3.0</span></label>
                <input type="range" min="1" max="10" step="0.5" value="3.0" oninput="updateSettings('size', this.value)">
            </div>
            <div class="setting-item">
                <label>点密度 (显示百分比): <span id="val-density">10%</span></label>
                <input type="range" min="0" max="100" step="1" value="10" oninput="updateSettings('density', this.value)">
            </div>
        </div>

        <!-- 姿态面板 (新增) -->
        <div id="attitude-panel" class="panel">
            <div style="width:100%; font-weight:bold; color:#fff; margin-bottom:5px;">实时姿态</div>
            <div id="attitude-container"></div>
            <div class="attitude-label" id="attitude-text">R: 0° P: 0° Y: 0°</div>
        </div>
        
        <!-- 图表控制栏 -->
        <div id="chart-controls">
            <span style="color:#4db8ff; font-weight:bold;">数据项:</span>
            <label><input type="checkbox" value="spd" checked onchange="handleDataToggle()"> 速度</label>
            <label><input type="checkbox" value="alt" checked onchange="handleDataToggle()"> 高度</label>
            <label><input type="checkbox" value="volt" onchange="handleDataToggle()"> 电压</label>
            <label><input type="checkbox" value="curr" onchange="handleDataToggle()"> 电流</label>
            <label><input type="checkbox" value="roll" onchange="handleDataToggle()"> 横滚</label>
            <label><input type="checkbox" value="pitch" onchange="handleDataToggle()"> 俯仰</label>
        </div>
    </div>

    <div id="tooltip"></div>
    <div id="three-container"></div>
    <div id="chart-container"></div>

<script>
    // --- 全局变量 ---
    let scene, camera, renderer, controls, raycaster, mouse;
    let trajectoryGroup = null; 
    let visiblePointsMesh = null;
    let fullData = []; 
    let mapTiles = [];
    let myChart = null;
    let centerCoord = { lat: 0, lng: 0 };
    
    // 播放控制相关
    let isPlaying = false;
    let playbackIndex = 0;
    let playbackSpeed = 5;
    let mainPlaneMesh = null; // 主场景中的飞机
    
    // 姿态小窗口相关
    let attScene, attCamera, attRenderer, attPlaneMesh;

    let config = { pointSize: 3.0, density: 10 };
    const R_EARTH = 6378137;
    const FIELD_LABELS = {
        'spd': { label: '速度', unit: 'km/h' },
        'alt': { label: '高度', unit: 'm' },
        'volt': { label: '电压', unit: 'V' },
        'curr': { label: '电流', unit: 'A' },
        'roll': { label: '横滚', unit: '°' },
        'pitch': { label: '俯仰', unit: '°' }
    };

    initThree();
    initAttitudeView(); // 初始化姿态小窗口
    initChart();
    
    // 事件监听
    document.getElementById('fileInput').addEventListener('change', e => {
        if(e.target.files[0]) document.getElementById('fileName').innerText = e.target.files[0].name;
    });
    window.addEventListener('resize', onWindowResize, false);
    window.addEventListener('mousemove', onMouseMove, false);
    
    // 速度滑块监听
    document.getElementById('speed-slider').addEventListener('input', function(e) {
        playbackSpeed = parseInt(e.target.value);
        document.getElementById('speed-val').innerText = playbackSpeed + 'x';
    });

    // --- 辅助函数 ---
    function formatTime(seconds) {
        if (seconds < 0) seconds = 0;
        const h = Math.floor(seconds / 3600);
        const m = Math.floor((seconds % 3600) / 60);
        const s = Math.floor(seconds % 60);
        return `${h.toString().padStart(2, '0')}:${m.toString().padStart(2, '0')}:${s.toString().padStart(2, '0')}`;
    }

    function handleDataToggle() {
        updateChartSeries();
        hoveredIndex = -1; 
    }

    // --- 1. Three.js 主场景 ---
    function initThree() {
        const container = document.getElementById('three-container');
        scene = new THREE.Scene();
        scene.background = new THREE.Color(0x111111);
        scene.fog = new THREE.Fog(0x111111, 200, 5000);

        camera = new THREE.PerspectiveCamera(45, container.clientWidth / container.clientHeight, 1, 20000);
        camera.position.set(0, 100, 200);

        renderer = new THREE.WebGLRenderer({ antialias: true });
        renderer.setPixelRatio(window.devicePixelRatio);
        renderer.setSize(container.clientWidth, container.clientHeight);
        container.appendChild(renderer.domElement);

        controls = new THREE.OrbitControls(camera, renderer.domElement);
        controls.enableDamping = true;
        controls.dampingFactor = 0.05;
        controls.maxPolarAngle = Math.PI / 2 - 0.02;
        controls.zoomSpeed = 0.3; 
        controls.rotateSpeed = 0.5;

        raycaster = new THREE.Raycaster();
        raycaster.params.Points.threshold = 5.0; 
        mouse = new THREE.Vector2(-999, -999);

        // 灯光
        scene.add(new THREE.AmbientLight(0xffffff, 0.6));
        const dir = new THREE.DirectionalLight(0xffffff, 0.8);
        dir.position.set(100, 200, 50);
        scene.add(dir);

        scene.add(new THREE.GridHelper(2000, 100, 0x333333, 0x222222));

        // 初始化主场景飞机 (默认隐藏)
        mainPlaneMesh = createCessnaMesh(); // 使用新的塞斯纳模型
        mainPlaneMesh.visible = false;
        scene.add(mainPlaneMesh);

        animate();
    }

    // --- 2. 姿态小窗口 (Attitude View) ---
    function initAttitudeView() {
        const container = document.getElementById('attitude-container');
        attScene = new THREE.Scene();
        
        // 调整相机位置为右后方 (Quarter View)
        // 拉近相机距离,使模型在视图中更大
        attCamera = new THREE.PerspectiveCamera(50, container.clientWidth / container.clientHeight, 0.1, 1000);
        attCamera.position.set(20, 15, 30); // 调整相机位置,更近
        attCamera.lookAt(0, 0, 0);

        attRenderer = new THREE.WebGLRenderer({ alpha: true, antialias: true });
        attRenderer.setSize(container.clientWidth, container.clientHeight);
        container.appendChild(attRenderer.domElement);

        // 灯光
        attScene.add(new THREE.AmbientLight(0xffffff, 0.8));
        const light = new THREE.DirectionalLight(0xffffff, 1);
        light.position.set(10, 20, 10);
        attScene.add(light);

        // 飞机模型
        attPlaneMesh = createCessnaMesh(); // 使用新的塞斯纳模型
        // 放大模型以填满约 3/4 窗口
        attPlaneMesh.scale.set(3, 3, 3); 
        attScene.add(attPlaneMesh);
    }

    // 创建塞斯纳风格飞机模型 (面向 -Z)
    function createCessnaMesh() {
        const group = new THREE.Group();
        const whiteMat = new THREE.MeshPhongMaterial({ color: 0xffffff, flatShading: true });
        const blueMat = new THREE.MeshPhongMaterial({ color: 0x4db8ff, flatShading: true });
        const darkMat = new THREE.MeshPhongMaterial({ color: 0x333333, flatShading: true });

        // 1. 机身 (白色圆柱)
        // 使用 CylinderGeometry(radiusTop, radiusBottom, height)
        // 我们需要 Top=0.8(Engine/Nose), Bottom=0.4(Tail) 以符合塞斯纳前粗后细的特征。
        // 默认Cylinder面向Y轴。
        // 我们需要让 Top 指向 -Z (正北),Bottom 指向 +Z。
        // rotateX(-PI/2) 将 +Y (Top) 旋转至 -Z。
        const fuselageGeo = new THREE.CylinderGeometry(0.8, 0.4, 8, 12);
        fuselageGeo.rotateX(-Math.PI / 2); // 旋转 -90度,使机头朝向 -Z,机身水平
        const fuselage = new THREE.Mesh(fuselageGeo, whiteMat);
        group.add(fuselage);

        // 2. 机头/引擎 (蓝色)
        // 同样逻辑,水平摆放
        const noseGeo = new THREE.CylinderGeometry(0.4, 0.8, 1, 12);
        noseGeo.rotateX(-Math.PI / 2); 
        const nose = new THREE.Mesh(noseGeo, blueMat);
        nose.position.set(0, 0, -4.5); // 移动到最前端 (-Z方向)
        group.add(nose);

        // 3. 螺旋桨 (深色)
        const propGeo = new THREE.BoxGeometry(4, 0.1, 0.2);
        const prop = new THREE.Mesh(propGeo, darkMat);
        prop.position.set(0, 0, -5.05);
        group.add(prop);

        // 4. 主翼 (上单翼,蓝色)
        const wingGeo = new THREE.BoxGeometry(10, 0.2, 1.8);
        const wing = new THREE.Mesh(wingGeo, blueMat);
        wing.position.set(0, 1.2, -1.5); // 上方且略靠前
        group.add(wing);

        // 5. 尾翼 (蓝色)
        // 水平尾翼
        const hTailGeo = new THREE.BoxGeometry(3.5, 0.1, 1.2);
        const hTail = new THREE.Mesh(hTailGeo, blueMat);
        hTail.position.set(0, 0.5, 3.5); // 后方 (+Z方向)
        group.add(hTail);

        // 垂直尾翼
        const vTailGeo = new THREE.BoxGeometry(0.1, 2, 1.5);
        const vTail = new THREE.Mesh(vTailGeo, blueMat);
        vTail.position.set(0, 1.5, 3.5);
        group.add(vTail);
        
        // 6. 驾驶舱窗户 (深色)
        const cockpitGeo = new THREE.BoxGeometry(1.3, 0.7, 1.5); 
        const cockpit = new THREE.Mesh(cockpitGeo, darkMat);
        cockpit.position.set(0, 0.9, -1.5); // 机身上方,略靠前
        group.add(cockpit);

        return group;
    }

    // --- 3. 动画循环 ---
    function animate() {
        requestAnimationFrame(animate);
        controls.update();

        // 播放逻辑
        if (isPlaying && fullData.length > 0) {
            // 根据倍速增加索引
            playbackIndex += (playbackSpeed * 0.1); // 0.1 是时间缩放因子
            if (playbackIndex >= fullData.length - 1) {
                playbackIndex = fullData.length - 1;
                isPlaying = false; // 播放结束
                document.getElementById('btn-play').innerText = '▶';
            }
            updatePlaybackState(Math.floor(playbackIndex));
        }

        // 渲染主场景
        renderRaycaster(); 
        renderer.render(scene, camera);

        // 渲染姿态小窗口
        if (attRenderer) attRenderer.render(attScene, attCamera);
    }

    // --- 4. 播放控制逻辑 ---
    function togglePlayback() {
        if (fullData.length === 0) return;
        isPlaying = !isPlaying;
        
        const btn = document.getElementById('btn-play');
        btn.innerText = isPlaying ? '⏸' : '▶';

        if (isPlaying) {
            mainPlaneMesh.visible = true;
            if (playbackIndex >= fullData.length - 1) playbackIndex = 0; // 重播
        }
    }

    function stopPlayback() {
        isPlaying = false;
        playbackIndex = 0;
        document.getElementById('btn-play').innerText = '▶';
        mainPlaneMesh.visible = false;
        updatePlaybackState(0);
    }

    function scrubPlayback(val) {
        if (fullData.length === 0) return;
        playbackIndex = parseInt(val);
        // 如果拖动时正在播放,暂停一下体验更好,或者直接更新位置
        updatePlaybackState(playbackIndex);
        if (!isPlaying) mainPlaneMesh.visible = true; // 拖动时显示飞机
    }

    function updatePlaybackState(index) {
        if (!fullData[index]) return;
        const point = fullData[index];

        // 1. 更新进度条 UI
        document.getElementById('progress-bar').value = index;
        
        // 2. 更新时间显示
        if (fullData.length > 0) {
            const startTime = fullData[0].time;
            const currentSeconds = (point.time - startTime) / 1000000;
            document.getElementById('playback-time').innerText = formatTime(currentSeconds);
        }

        // 3. 更新飞机位置与姿态 (主场景)
        const m = latLonToMeters(point.lat, point.lng, centerCoord.lat, centerCoord.lng);
        mainPlaneMesh.position.set(m.x, point.alt, -m.y);
        
        // 旋转顺序 YXZ (Yaw -> Pitch -> Roll) 常见于航空
        // Pixhawk 数据通常是度数
        const radRoll = THREE.MathUtils.degToRad(point.roll);
        const radPitch = THREE.MathUtils.degToRad(point.pitch);
        const radYaw = THREE.MathUtils.degToRad(-point.yaw); // 负号因为 WebGL 坐标系差异

        // 更新主飞机旋转
        mainPlaneMesh.rotation.order = 'YXZ'; 
        mainPlaneMesh.rotation.y = radYaw; 
        mainPlaneMesh.rotation.x = radPitch;
        mainPlaneMesh.rotation.z = -radRoll; // 负号修正

        // 4. 更新小窗口姿态飞机
        if (attPlaneMesh) {
            attPlaneMesh.rotation.order = 'YXZ';
            // 因为模型已经默认朝向 -Z (正北),直接应用姿态数据即可,无需额外旋转
            attPlaneMesh.rotation.y = Math.PI; // 让模型背对相机,或者旋转到便于观察的角度?
            // 其实小窗口里我们希望能看清姿态。
            // 之前的相机位置是 (30, 20, 50),看着 (0,0,0)。
            // 如果 Yaw=0 (North, -Z),模型朝向 -Z (远离相机)。我们看到的是屁股。
            // 为了更好地观察姿态,通常我们希望模型稍微侧一点。
            // 这里我们保持绝对姿态同步,相机位置已经提供了侧后方视角。
            attPlaneMesh.rotation.y = radYaw; 
            attPlaneMesh.rotation.x = radPitch;
            attPlaneMesh.rotation.z = -radRoll; 
        }
        
        // 更新文字
        document.getElementById('attitude-text').innerText = 
            `R: ${point.roll.toFixed(1)}° P: ${point.pitch.toFixed(1)}° Y: ${point.yaw.toFixed(1)}°`;

        // 5. 联动 ECharts
        if (myChart) {
            myChart.dispatchAction({
                type: 'showTip',
                seriesIndex: 0,
                dataIndex: index
            });
        }
    }

    // --- 5. 交互逻辑 (Raycaster) ---
    function onMouseMove(event) {
        const container = document.getElementById('three-container');
        if (event.clientY > container.clientHeight) {
            mouse.x = -999; mouse.y = -999; return;
        }
        mouse.x = (event.clientX / container.clientWidth) * 2 - 1;
        mouse.y = -(event.clientY / container.clientHeight) * 2 + 1;
        
        const tooltip = document.getElementById('tooltip');
        if (tooltip.style.display === 'block') {
            tooltip.style.left = (event.clientX + 15) + 'px';
            tooltip.style.top = (event.clientY + 15) + 'px';
        }
    }

    let hoveredIndex = -1;
    function renderRaycaster() {
        if (!visiblePointsMesh) return;
        // 如果正在播放,不进行鼠标悬停检测,避免闪烁
        if (isPlaying) return; 

        raycaster.setFromCamera(mouse, camera);
        const intersects = raycaster.intersectObject(visiblePointsMesh);
        const tooltip = document.getElementById('tooltip');
        
        if (intersects.length > 0) {
            const index = intersects[0].index; 
            const realDataIndex = visiblePointsMesh.userData.indices[index];
            const point = fullData[realDataIndex];

            if (point && realDataIndex !== hoveredIndex) {
                hoveredIndex = realDataIndex;
                tooltip.style.display = 'block';
                let content = `<div style="color:#4db8ff; font-weight:bold; margin-bottom:5px; border-bottom:1px solid #444; padding-bottom:3px;">
                                数据点 #${point.index}</div>`;
                
                const checks = document.querySelectorAll('#chart-controls input:checked');
                checks.forEach(chk => {
                    const key = chk.value;
                    const meta = FIELD_LABELS[key];
                    if (meta && point[key] !== undefined) {
                        const val = typeof point[key] === 'number' ? point[key].toFixed(2) : point[key];
                        content += `<div><span style="color:#aaa;">${meta.label}:</span> ${val} ${meta.unit}</div>`;
                    }
                });
                if (point.time !== undefined && fullData.length > 0) {
                    const startTime = fullData[0].time;
                    let flightSeconds = (point.time - startTime) / 1000000;
                    if (flightSeconds < 0) flightSeconds = 0;
                    content += `<div><span style="color:#aaa;">飞行时间:</span> <span style="color:#fff; font-family:monospace;">${formatTime(flightSeconds)}</span></div>`;
                }
                tooltip.innerHTML = content;
                
                // 联动 ECharts
                if (myChart) myChart.dispatchAction({ type: 'showTip', seriesIndex: 0, dataIndex: realDataIndex });
                
                // 联动姿态模型 (悬停时也更新姿态)
                updatePlaybackState(realDataIndex);
                mainPlaneMesh.visible = true; // 悬停时显示飞机在那个点
            }
        } else {
            if (hoveredIndex !== -1) {
                hoveredIndex = -1;
                tooltip.style.display = 'none';
                if(!isPlaying) mainPlaneMesh.visible = false; // 移开鼠标隐藏
            }
        }
    }

    // --- 数据处理与渲染 ---
    function uploadLog() {
        const fileInput = document.getElementById('fileInput');
        if (!fileInput.files[0]) return alert('请先选择文件');
        document.getElementById('loadingMsg').style.display = 'block';

        const formData = new FormData();
        formData.append('file', fileInput.files[0]);

        fetch('/upload', { method: 'POST', body: formData })
            .then(res => res.json())
            .then(res => {
                document.getElementById('loadingMsg').style.display = 'none';
                if (res.error) return alert(res.error);
                
                fullData = res.data;
                centerCoord = res.center;
                
                // 初始化进度条范围
                const pb = document.getElementById('progress-bar');
                pb.max = fullData.length - 1;
                pb.value = 0;
                
                updateStatsPanel(res.stats);
                loadMapTiles(centerCoord.lat, centerCoord.lng);
                renderTrajectory();
                updateChartSeries();
                
                // 默认显示第一个点的姿态
                updatePlaybackState(0);
            })
            .catch(err => {
                console.error(err);
                document.getElementById('loadingMsg').style.display = 'none';
                alert('处理失败');
            });
    }

    function updateStatsPanel(stats) {
        const div = document.getElementById('stats-content');
        const rows = [
            ['总里程', `${stats.total_dist_m} m`],
            ['总爬升', `${stats.total_climb_m} m`],
            ['速度范围', `${stats.min_spd} - ${stats.max_spd} km/h`],
            ['高度范围', `${stats.min_alt} - ${stats.max_alt} m`],
            ['初始电压', `${stats.start_volt} V`],
            ['结束电压', `${stats.end_volt} V`],
            ['消耗电量', `${stats.consumed_mah} mAh`],
            ['能耗效率', `${stats.efficiency} mAh/km`]
        ];
        let html = '';
        rows.forEach(r => { html += `<div class="stat-row"><span>${r[0]}</span><span class="stat-val">${r[1]}</span></div>`; });
        div.innerHTML = html;
        document.getElementById('stats-panel').style.display = 'block';
    }

    function getHeatColor(value, minVal, maxVal) {
        let t = (value - minVal) / (maxVal - minVal);
        t = Math.max(0, Math.min(1, t)); 
        const hue = (1.0 - t) * 240; 
        return new THREE.Color(`hsl(${hue}, 100%, 50%)`);
    }

    function latLonToMeters(lat, lon, centerLat, centerLon) {
        const x = (lon - centerLon) * (Math.PI * R_EARTH / 180.0);
        const y = (lat - centerLat) * (Math.PI * R_EARTH / 180.0);
        return { x, y };
    }

    function renderTrajectory() {
        if (!fullData || fullData.length === 0) return;
        if (trajectoryGroup) {
            scene.remove(trajectoryGroup);
            trajectoryGroup.traverse((child) => {
                if (child.geometry) child.geometry.dispose();
                if (child.material) {
                    if (Array.isArray(child.material)) child.material.forEach(m => m.dispose());
                    else child.material.dispose();
                }
            });
        }
        visiblePointsMesh = null;
        trajectoryGroup = new THREE.Group();

        const linePositions = [];
        const lineColors = [];
        const pointPositions = [];
        const pointColors = [];
        const pointIndices = [];

        let minSpd = Infinity, maxSpd = -Infinity;
        fullData.forEach(p => {
            if (p.spd < minSpd) minSpd = p.spd;
            if (p.spd > maxSpd) maxSpd = p.spd;
        });
        if (maxSpd === minSpd) maxSpd = minSpd + 1;

        for (let i = 0; i < fullData.length; i++) {
            const p = fullData[i];
            const m = latLonToMeters(p.lat, p.lng, centerCoord.lat, centerCoord.lng);
            linePositions.push(m.x, p.alt, -m.y);
            const color = getHeatColor(p.spd, minSpd, maxSpd);
            lineColors.push(color.r, color.g, color.b);
        }

        let step = 1;
        const density = parseFloat(config.density);
        if (density <= 0) step = Infinity; 
        else if (density >= 100) step = 1;
        else step = 100 / density;

        for (let i = 0; i < fullData.length; i += step) {
            const idx = Math.floor(i);
            if (idx >= fullData.length) break;
            const p = fullData[idx];
            const m = latLonToMeters(p.lat, p.lng, centerCoord.lat, centerCoord.lng);
            pointPositions.push(m.x, p.alt, -m.y);
            const color = getHeatColor(p.spd, minSpd, maxSpd);
            pointColors.push(color.r, color.g, color.b);
            pointIndices.push(idx); 
        }

        const lineGeo = new THREE.BufferGeometry();
        lineGeo.setAttribute('position', new THREE.Float32BufferAttribute(linePositions, 3));
        lineGeo.setAttribute('color', new THREE.Float32BufferAttribute(lineColors, 3));
        const lineMat = new THREE.LineBasicMaterial({ vertexColors: true, linewidth: 2, opacity: 0.6, transparent: true });
        trajectoryGroup.add(new THREE.Line(lineGeo, lineMat));

        if (pointPositions.length > 0) {
            const pointGeo = new THREE.BufferGeometry();
            pointGeo.setAttribute('position', new THREE.Float32BufferAttribute(pointPositions, 3));
            pointGeo.setAttribute('color', new THREE.Float32BufferAttribute(pointColors, 3));
            const pointMat = new THREE.PointsMaterial({ 
                size: parseFloat(config.pointSize), vertexColors: true, sizeAttenuation: false 
            });
            visiblePointsMesh = new THREE.Points(pointGeo, pointMat);
            visiblePointsMesh.userData = { indices: pointIndices };
            trajectoryGroup.add(visiblePointsMesh);
        }

        scene.add(trajectoryGroup);

        if (linePositions.length > 2) {
            controls.target.set(linePositions[0], linePositions[1], linePositions[2]);
            camera.position.set(linePositions[0] + 100, linePositions[1] + 100, linePositions[2] + 100);
            controls.update();
        }
    }

    function updateSettings(key, val) {
        config[key] = val;
        if (key === 'density') document.getElementById(`val-${key}`).innerText = val + '%';
        else document.getElementById(`val-${key}`).innerText = val;
        renderTrajectory(); 
    }

    // --- 地图瓦片逻辑 ---
    function deg2tile(lat, lon, zoom) {
        const lat_rad = lat * Math.PI / 180;
        const n = Math.pow(2, zoom);
        const xtile = Math.floor((lon + 180.0) / 360.0 * n);
        const ytile = Math.floor((1.0 - Math.asinh(Math.tan(lat_rad)) / Math.PI) / 2.0 * n);
        return { x: xtile, y: ytile };
    }
    function tile2deg(x, y, z) {
        const n = Math.pow(2, z);
        const lon_deg = x / n * 360.0 - 180.0;
        const lat_rad = Math.atan(Math.sinh(Math.PI * (1 - 2 * y / n)));
        const lat_deg = lat_rad * 180.0 / Math.PI;
        return { lat: lat_deg, lon: lon_deg };
    }
    function loadMapTiles(centerLat, centerLon) {
        mapTiles.forEach(t => scene.remove(t));
        mapTiles = [];
        const zoom = 18;
        const centerTile = deg2tile(centerLat, centerLon, zoom);
        const loader = new THREE.TextureLoader();
        const baseUrl = 'https://server.arcgisonline.com/ArcGIS/rest/services/World_Imagery/MapServer/tile/';
        for (let dx = -2; dx <= 2; dx++) {
            for (let dy = -2; dy <= 2; dy++) {
                const tx = centerTile.x + dx;
                const ty = centerTile.y + dy;
                const url = `${baseUrl}${zoom}/${ty}/${tx}`;
                const nw = tile2deg(tx, ty, zoom);
                const se = tile2deg(tx + 1, ty + 1, zoom);
                const pos = latLonToMeters((nw.lat + se.lat)/2, (nw.lon + se.lon)/2, centerLat, centerLon);
                const width = Math.abs((se.lon - nw.lon) * (Math.PI * R_EARTH / 180.0));
                const height = Math.abs((nw.lat - se.lat) * (Math.PI * R_EARTH / 180.0));
                loader.load(url, (texture) => {
                    const plane = new THREE.Mesh(new THREE.PlaneGeometry(width, height), new THREE.MeshBasicMaterial({ map: texture, side: THREE.DoubleSide }));
                    plane.rotation.x = -Math.PI / 2;
                    plane.position.set(pos.x, -0.5, -pos.y);
                    scene.add(plane);
                    mapTiles.push(plane);
                });
            }
        }
    }

    // --- ECharts ---
    function initChart() {
        myChart = echarts.init(document.getElementById('chart-container'), 'dark');
        window.addEventListener('resize', () => myChart.resize());
    }

    function updateChartSeries() {
        if (!fullData || fullData.length === 0) return;
        const inputs = document.querySelectorAll('#chart-controls input:checked');
        const selectedKeys = Array.from(inputs).map(i => i.value);
        
        let xAxisData = [];
        if (fullData.length > 0 && fullData[0].time !== undefined) {
            const startTime = fullData[0].time;
            xAxisData = fullData.map(p => {
                let sec = (p.time - startTime) / 1000000;
                if (sec < 0) sec = 0;
                return formatTime(sec);
            });
        } else {
            xAxisData = fullData.map(p => p.index);
        }

        const series = [];
        const yAxis = [
            { type: 'value', name: 'Left', position: 'left', splitLine: { show: false } },
            { type: 'value', name: 'Right', position: 'right', splitLine: { show: false } }
        ];

        const configMap = {
            'spd': { name: '速度 (km/h)', color: '#ff0000', axis: 0 },
            'alt': { name: '高度 (m)', color: '#00ff00', axis: 0 }, 
            'volt': { name: '电压 (V)', color: '#ffff00', axis: 1 }, 
            'curr': { name: '电流 (A)', color: '#ff00ff', axis: 1 },
            'roll': { name: 'Roll (°)', color: '#00ffff', axis: 1 },
            'pitch': { name: 'Pitch (°)', color: '#ffffff', axis: 1 }
        };

        selectedKeys.forEach(key => {
            const conf = configMap[key];
            series.push({
                name: conf.name, type: 'line', data: fullData.map(p => p[key]),
                yAxisIndex: conf.axis, showSymbol: false, smooth: true,
                lineStyle: { width: 1.5, color: conf.color }
            });
        });

        myChart.setOption({
            backgroundColor: '#222',
            tooltip: { trigger: 'axis', axisPointer: { type: 'cross' } },
            legend: { data: series.map(s => s.name), textStyle: { color: '#fff' } },
            grid: { left: 50, right: 50, top: 40, bottom: 30 },
            xAxis: { type: 'category', data: xAxisData, name: '飞行时间', nameTextStyle: { color: '#aaa' } },
            yAxis: yAxis, series: series
        }, true); 
    }

    function onWindowResize() {
        const container = document.getElementById('three-container');
        camera.aspect = container.clientWidth / container.clientHeight;
        camera.updateProjectionMatrix();
        renderer.setSize(container.clientWidth, container.clientHeight);
        if(myChart) myChart.resize();
    }
</script>
</body>
</html>

3. 环境依赖 (Python)

requirements.txt

Flask==2.3.3
Werkzeug==2.3.7
pymavlink==2.4.41

4. 自动化启动脚本 (Shell)

run.sh此脚本会自动检测 Python 环境,创建虚拟环境,安装依赖并运行服务。

#!/bin/bash

# 设置端口
PORT=5555
VENV_DIR="venv"

echo "=== Pixhawk 3D Trajectory Server Deployment ==="

# 1. 检查 Python3
if ! command -v python3 &> /dev/null; then
    echo "Error: Python3 not found. Please install it (sudo apt install python3 python3-venv)."
    exit 1
fi

# 2. 创建虚拟环境
if [ ! -d "$VENV_DIR" ]; then
    echo "Creating virtual environment..."
    python3 -m venv $VENV_DIR
fi

# 3. 激活环境并安装依赖
echo "Activating venv and installing requirements..."
source $VENV_DIR/bin/activate

if [ -f "requirements.txt" ]; then
    pip install -r requirements.txt
else
    echo "Warning: requirements.txt not found. Installing Flask manually."
    pip install Flask
fi

# 4. 运行服务
echo "Starting server on port $PORT..."
echo "Access via: http://<server-ip>:$PORT"

# 使用 nohup 后台运行,或者直接前台运行 (此处演示前台运行以便查看日志)
python app.py