@@ -14,6 +14,34 @@ class SetStateType(TypedDict):
1414 state : str
1515
1616
17+ GLOBAL_MESSAGE_LISTENERS = ["HEARTBEAT" , "STATUSTEXT" , "GLOBAL_POSITION_INT" ]
18+
19+ STATES_MESSAGE_LISTENERS = {
20+ "dashboard" : [
21+ "VFR_HUD" ,
22+ "BATTERY_STATUS" ,
23+ "ATTITUDE" ,
24+ "ALTITUDE" ,
25+ "NAV_CONTROLLER_OUTPUT" ,
26+ "SYS_STATUS" ,
27+ "GPS_RAW_INT" ,
28+ "RC_CHANNELS" ,
29+ "ESC_TELEMETRY_5_TO_8" ,
30+ "MISSION_CURRENT" ,
31+ "EKF_STATUS_REPORT" ,
32+ "VIBRATION" ,
33+ ],
34+ "missions" : [
35+ "NAV_CONTROLLER_OUTPUT" ,
36+ ],
37+ "graphs" : ["VFR_HUD" , "ATTITUDE" , "SYS_STATUS" ],
38+ "config.flight_modes" : [
39+ "RC_CHANNELS" ,
40+ ],
41+ "config.rc" : ["RC_CHANNELS" ],
42+ }
43+
44+
1745@socketio .on ("set_state" )
1846def set_state (data : SetStateType ) -> None :
1947 """
@@ -31,78 +59,47 @@ def set_state(data: SetStateType) -> None:
3159
3260 droneStatus .state = newState
3361
34- message_listeners = {
35- "dashboard" : [
36- "VFR_HUD" ,
37- "BATTERY_STATUS" ,
38- "GLOBAL_POSITION_INT" ,
39- "ATTITUDE" ,
40- "ALTITUDE" ,
41- "NAV_CONTROLLER_OUTPUT" ,
42- "HEARTBEAT" ,
43- "SYS_STATUS" ,
44- "GPS_RAW_INT" ,
45- "RC_CHANNELS" ,
46- "ESC_TELEMETRY_5_TO_8" ,
47- "MISSION_CURRENT" ,
48- "EKF_STATUS_REPORT" ,
49- "VIBRATION" ,
50- ],
51- "missions" : ["GLOBAL_POSITION_INT" , "NAV_CONTROLLER_OUTPUT" , "HEARTBEAT" ],
52- "graphs" : ["VFR_HUD" , "ATTITUDE" , "SYS_STATUS" ],
53- "config.flight_modes" : ["RC_CHANNELS" , "HEARTBEAT" ],
54- "config.rc" : ["RC_CHANNELS" , "HEARTBEAT" ],
55- }
56-
5762 droneStatus .drone .logger .info (f"Changing state to { droneStatus .state } " )
5863
59- # Always send STATUSTEXT messages
60- droneStatus .drone .addMessageListener ("STATUSTEXT" , sendMessage )
64+ # Reset all data streams
65+ droneStatus .drone .stopAllDataStreams ()
66+
67+ # Always setup position stream to get GLOBAL_POSITION_INT messages
68+ droneStatus .drone .setupSingleDataStream (mavutil .mavlink .MAV_DATA_STREAM_POSITION )
69+
70+ for message in GLOBAL_MESSAGE_LISTENERS :
71+ droneStatus .drone .addMessageListener (message , sendMessage )
6172
6273 if droneStatus .state == "dashboard" :
6374 droneStatus .drone .setupDataStreams ()
64- for message in message_listeners ["dashboard" ]:
75+ for message in STATES_MESSAGE_LISTENERS ["dashboard" ]:
6576 droneStatus .drone .addMessageListener (message , sendMessage )
66- if droneStatus .state == "missions" :
67- droneStatus .drone .stopAllDataStreams ()
77+ elif droneStatus .state == "missions" :
6878 droneStatus .drone .setupSingleDataStream (
6979 mavutil .mavlink .MAV_DATA_STREAM_EXTENDED_STATUS
7080 )
71- droneStatus .drone .setupSingleDataStream (
72- mavutil .mavlink .MAV_DATA_STREAM_POSITION
73- )
74- for message in message_listeners ["missions" ]:
81+ for message in STATES_MESSAGE_LISTENERS ["missions" ]:
7582 droneStatus .drone .addMessageListener (message , sendMessage )
7683 elif droneStatus .state == "graphs" :
77- droneStatus .drone .stopAllDataStreams ()
78-
7984 droneStatus .drone .setupSingleDataStream (
8085 mavutil .mavlink .MAV_DATA_STREAM_EXTENDED_STATUS
8186 )
8287 droneStatus .drone .setupSingleDataStream (mavutil .mavlink .MAV_DATA_STREAM_EXTRA1 )
8388 droneStatus .drone .setupSingleDataStream (mavutil .mavlink .MAV_DATA_STREAM_EXTRA2 )
8489
85- for message in message_listeners ["graphs" ]:
90+ for message in STATES_MESSAGE_LISTENERS ["graphs" ]:
8691 droneStatus .drone .addMessageListener (message , sendMessage )
87- elif droneStatus .state == "params" :
88- droneStatus .drone .stopAllDataStreams ()
89- elif droneStatus .state == "config" :
90- droneStatus .drone .stopAllDataStreams ()
9192 elif droneStatus .state == "config.flight_modes" :
92- droneStatus .drone .stopAllDataStreams ()
93-
9493 droneStatus .drone .sendDataStreamRequestMessage (
9594 mavutil .mavlink .MAV_DATA_STREAM_RC_CHANNELS , 2
9695 )
9796
98- for message in message_listeners ["config.flight_modes" ]:
97+ for message in STATES_MESSAGE_LISTENERS ["config.flight_modes" ]:
9998 droneStatus .drone .addMessageListener (message , sendMessage )
10099 elif droneStatus .state == "config.rc" :
101- droneStatus .drone .stopAllDataStreams ()
102-
103100 droneStatus .drone .sendDataStreamRequestMessage (
104101 mavutil .mavlink .MAV_DATA_STREAM_RC_CHANNELS , 4
105102 )
106103
107- for message in message_listeners ["config.rc" ]:
104+ for message in STATES_MESSAGE_LISTENERS ["config.rc" ]:
108105 droneStatus .drone .addMessageListener (message , sendMessage )
0 commit comments