|
1 | 1 | using System.Collections.Concurrent; |
2 | | -using System.Collections.Generic; |
3 | 2 | using System.Threading.Tasks; |
4 | 3 |
|
5 | 4 | namespace MissionPlanner.ArduPilot.Mavlink |
@@ -31,45 +30,52 @@ public GimbalManagerProtocol(MAVLinkInterface mavint) |
31 | 30 | this.mavint = mavint; |
32 | 31 | } |
33 | 32 |
|
| 33 | + private bool first_discover = true; |
34 | 34 | public void Discover() |
35 | 35 | { |
| 36 | + if (first_discover) |
| 37 | + { |
| 38 | + first_discover = false; |
| 39 | + mavint.OnPacketReceived += MessagesHandler; |
| 40 | + } |
| 41 | + |
36 | 42 | mavint.doCommand(0, 0, MAVLink.MAV_CMD.REQUEST_MESSAGE, |
37 | 43 | (float)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_INFORMATION, |
38 | 44 | 0, 0, 0, 0, 0, 0, false); |
| 45 | + } |
39 | 46 |
|
40 | | - mavint.OnPacketReceived += (sender, message) => |
| 47 | + private void MessagesHandler(object sender, MAVLink.MAVLinkMessage message) |
| 48 | + { |
| 49 | + if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_INFORMATION) |
41 | 50 | { |
42 | | - if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_INFORMATION) |
43 | | - { |
44 | | - var gmi = (MAVLink.mavlink_gimbal_manager_information_t)message.data; |
| 51 | + var gmi = (MAVLink.mavlink_gimbal_manager_information_t)message.data; |
45 | 52 |
|
46 | | - ManagerInfo[gmi.gimbal_device_id] = gmi; |
47 | | - if (!ManagerInfo.ContainsKey(0) || gmi.gimbal_device_id <= ManagerInfo[0].gimbal_device_id) |
48 | | - { |
49 | | - ManagerInfo[0] = gmi; |
50 | | - } |
| 53 | + ManagerInfo[gmi.gimbal_device_id] = gmi; |
| 54 | + if (!ManagerInfo.ContainsKey(0) || gmi.gimbal_device_id <= ManagerInfo[0].gimbal_device_id) |
| 55 | + { |
| 56 | + ManagerInfo[0] = gmi; |
51 | 57 | } |
| 58 | + } |
52 | 59 |
|
53 | | - if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_STATUS) |
| 60 | + if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_STATUS) |
| 61 | + { |
| 62 | + var gms = (MAVLink.mavlink_gimbal_manager_status_t)message.data; |
| 63 | + ManagerStatus[gms.gimbal_device_id] = gms; |
| 64 | + if (!ManagerStatus.ContainsKey(0) || gms.gimbal_device_id <= ManagerStatus[0].gimbal_device_id) |
54 | 65 | { |
55 | | - var gms = (MAVLink.mavlink_gimbal_manager_status_t)message.data; |
56 | | - ManagerStatus[gms.gimbal_device_id] = gms; |
57 | | - if (!ManagerStatus.ContainsKey(0) || gms.gimbal_device_id <= ManagerStatus[0].gimbal_device_id) |
58 | | - { |
59 | | - ManagerStatus[0] = gms; |
60 | | - } |
| 66 | + ManagerStatus[0] = gms; |
61 | 67 | } |
| 68 | + } |
62 | 69 |
|
63 | | - if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_DEVICE_ATTITUDE_STATUS) |
| 70 | + if (message.msgid == (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_DEVICE_ATTITUDE_STATUS) |
| 71 | + { |
| 72 | + var gds = (MAVLink.mavlink_gimbal_device_attitude_status_t)message.data; |
| 73 | + GimbalStatus[gds.gimbal_device_id] = gds; |
| 74 | + if (!GimbalStatus.ContainsKey(0) || gds.gimbal_device_id <= GimbalStatus[0].gimbal_device_id) |
64 | 75 | { |
65 | | - var gds = (MAVLink.mavlink_gimbal_device_attitude_status_t)message.data; |
66 | | - GimbalStatus[gds.gimbal_device_id] = gds; |
67 | | - if (!GimbalStatus.ContainsKey(0) || gds.gimbal_device_id <= GimbalStatus[0].gimbal_device_id) |
68 | | - { |
69 | | - GimbalStatus[0] = gds; |
70 | | - } |
| 76 | + GimbalStatus[0] = gds; |
71 | 77 | } |
72 | | - }; |
| 78 | + } |
73 | 79 | } |
74 | 80 |
|
75 | 81 | public bool HasCapability(MAVLink.GIMBAL_MANAGER_CAP_FLAGS flags, byte gimbal_device_id = 0) |
|
0 commit comments