Skip to content

Commit 56a2a6b

Browse files
committed
GimbalManagerProtocol: periodically discover
1 parent f8b8e5e commit 56a2a6b

File tree

2 files changed

+32
-25
lines changed

2 files changed

+32
-25
lines changed

ExtLibs/ArduPilot/CurrentState.cs

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4411,6 +4411,7 @@ public void UpdateCurrentSettings(Action<CurrentState> bs, bool updatenow,
44114411
MAV.sysid,
44124412
MAV.compid); // request rc info
44134413
MAV.Camera?.RequestMessageIntervals(MAV.cs.ratestatus); // use ratestatus until we create a new setting for this
4414+
MAV.GimbalManager?.Discover();
44144415
}
44154416
catch
44164417
{

ExtLibs/ArduPilot/Mavlink/GimbalManagerProtocol.cs

Lines changed: 31 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
using System.Collections.Concurrent;
2-
using System.Collections.Generic;
32
using System.Threading.Tasks;
43

54
namespace MissionPlanner.ArduPilot.Mavlink
@@ -31,45 +30,52 @@ public GimbalManagerProtocol(MAVLinkInterface mavint)
3130
this.mavint = mavint;
3231
}
3332

33+
private bool first_discover = true;
3434
public void Discover()
3535
{
36+
if (first_discover)
37+
{
38+
first_discover = false;
39+
mavint.OnPacketReceived += MessagesHandler;
40+
}
41+
3642
mavint.doCommand(0, 0, MAVLink.MAV_CMD.REQUEST_MESSAGE,
3743
(float)MAVLink.MAVLINK_MSG_ID.GIMBAL_MANAGER_INFORMATION,
3844
0, 0, 0, 0, 0, 0, false);
45+
}
3946

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)
4150
{
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;
4552

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;
5157
}
58+
}
5259

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)
5465
{
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;
6167
}
68+
}
6269

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)
6475
{
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;
7177
}
72-
};
78+
}
7379
}
7480

7581
public bool HasCapability(MAVLink.GIMBAL_MANAGER_CAP_FLAGS flags, byte gimbal_device_id = 0)

0 commit comments

Comments
 (0)