Upload files to 'src/unitdev01/unitdev01'

chiyu
ken910606 12 months ago
parent fa7689eaf5
commit d32610d700

@ -4,8 +4,7 @@ from rclpy.node import Node
from PyQt6.QtWidgets import (QApplication, QMainWindow, QVBoxLayout, QHBoxLayout,
QWidget, QLabel, QSplitter, QScrollArea,
QSizePolicy, QApplication)
from PyQt6.QtCore import Qt, QTimer, QObject, pyqtSignal, QUrl
from PyQt6.QtGui import QColor
from PyQt6.QtCore import Qt, QTimer, QObject, pyqtSignal
from PyQt6.QtWebEngineWidgets import QWebEngineView
import math
import re
@ -14,8 +13,8 @@ import sys
from threading import Lock
from geometry_msgs.msg import Point, Vector3
from sensor_msgs.msg import BatteryState, NavSatFix, Imu
from std_msgs.msg import String, Float64
from mavros_msgs.msg import VfrHud
from std_msgs.msg import Float64
from mavros_msgs.msg import VfrHud, State
class DroneSignals(QObject):
update_signal = pyqtSignal(str, str, object) # (msg_type, drone_id, data)
@ -62,10 +61,10 @@ class DroneMonitor(Node):
lambda msg, did=drone_id: self.battery_callback(did, msg),
10
),
'flightMode': self.create_subscription(
String,
f'{base_topic}/flightMode',
lambda msg, did=drone_id: self.mode_callback(did, msg),
'state': self.create_subscription(
State,
f'{base_topic}/state',
lambda msg, did=drone_id: self.state_callback(did, msg),
10
),
'global': self.create_subscription(
@ -135,14 +134,17 @@ class DroneMonitor(Node):
'voltage': msg.voltage
})
def mode_callback(self, drone_id, msg):
self.signals.update_signal.emit('mode', drone_id, msg.data)
def state_callback(self, drone_id, msg):
self.signals.update_signal.emit('state', drone_id, {
'mode': msg.mode,
'armed': msg.armed
})
def gps_callback(self, drone_id, msg):
self.signals.update_signal.emit('gps', drone_id, {
'lat': msg.latitude,
'lon': msg.longitude
,'alt': msg.altitude
'lon': msg.longitude,
'alt': msg.altitude
})
def local_vel_callback(self, drone_id, msg):
@ -236,7 +238,7 @@ class ControlStationUI(QMainWindow):
<body>
<div id="map"></div>
<script>
var map = L.map('map').setView([0, 0], 2);
var map = L.map('map').setView([0, 0], 16);
L.tileLayer('https://{s}.tile.openstreetmap.org/{z}/{x}/{y}.png', {
maxZoom: 19
}).addTo(map);
@ -260,7 +262,7 @@ class ControlStationUI(QMainWindow):
rotationOrigin: 'center'
}).addTo(map).bindPopup(id);
}
map.setView([lat, lon], 16);
map.setView([lat, lon]);
}
</script>
</body>
@ -365,8 +367,9 @@ class ControlStationUI(QMainWindow):
if not (panel := self.drones.get(drone_id)):
return
if msg_type == 'mode':
self.update_field(panel, drone_id, 'mode', f"{data}",
if msg_type == 'state':
mode = data['mode']
self.update_field(panel, drone_id, 'mode', f"{mode}",
'#FF5555' if '返航' in data else '#55FF55')
elif msg_type == 'battery':

Loading…
Cancel
Save