Skip to content

Commit 174bec3

Browse files
committed
GimbalVideoControl: draw tracking feedback
1 parent c7a393e commit 174bec3

File tree

1 file changed

+52
-1
lines changed

1 file changed

+52
-1
lines changed

Controls/GimbalVideoControl.cs

Lines changed: 52 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,57 @@ private void RenderFrame(object sender, MPBitmap image)
174174
VideoBox.Image = new Bitmap(
175175
image.Width, image.Height, 4 * image.Width,
176176
PixelFormat.Format32bppPArgb,
177-
image.LockBits(Rectangle.Empty, null, SKColorType.Bgra8888).Scan0);
177+
image.LockBits(Rectangle.Empty, null, SKColorType.Bgra8888).Scan0
178+
);
179+
180+
// Overlay tracking info
181+
var tracking_status = selectedCamera?.CameraTrackingImageStatus ?? new mavlink_camera_tracking_image_status_t();
182+
if (dragStartPoint.HasValue && dragEndPoint.HasValue)
183+
{
184+
var start = dragStartPoint.Value;
185+
var end = dragEndPoint.Value;
186+
using (var g = Graphics.FromImage(VideoBox.Image))
187+
{
188+
var x = (float)(Math.Min(start.x, end.x) + 1) * VideoBox.Image.Width / 2;
189+
var y = (float)(Math.Min(start.y, end.y) + 1) * VideoBox.Image.Height / 2;
190+
var w = (float)Math.Abs(start.x - end.x) * VideoBox.Image.Width / 2;
191+
var h = (float)Math.Abs(start.y - end.y) * VideoBox.Image.Height / 2;
192+
g.DrawRectangle(Pens.Red, x, y, w, h);
193+
}
194+
}
195+
else if (tracking_status.tracking_status == (byte)MAVLink.CAMERA_TRACKING_STATUS_FLAGS.ACTIVE &&
196+
(tracking_status.target_data & (byte)MAVLink.CAMERA_TRACKING_TARGET_DATA.RENDERED) == 0 && // Don't render if the target is already rendered
197+
(tracking_status.target_data & (byte)MAVLink.CAMERA_TRACKING_TARGET_DATA.IN_STATUS) != 0) // Only render if this status message contains the target data
198+
{
199+
if (tracking_status.tracking_mode == (byte)MAVLink.CAMERA_TRACKING_MODE.POINT &&
200+
!float.IsNaN(tracking_status.point_x) &&
201+
!float.IsNaN(tracking_status.point_y))
202+
{
203+
var x = tracking_status.point_x * VideoBox.Image.Width;
204+
var y = tracking_status.point_y * VideoBox.Image.Height;
205+
var size = float.IsNaN(tracking_status.radius) ? 10 : tracking_status.radius;
206+
using (var g = Graphics.FromImage(VideoBox.Image))
207+
{
208+
g.DrawEllipse(Pens.Red, (int)x - size / 2, (int)y - size / 2, size, size);
209+
}
210+
}
211+
else if (tracking_status.tracking_mode == (byte)MAVLink.CAMERA_TRACKING_MODE.RECTANGLE &&
212+
!float.IsNaN(tracking_status.rec_top_x) &&
213+
!float.IsNaN(tracking_status.rec_top_y) &&
214+
!float.IsNaN(tracking_status.rec_bottom_x) &&
215+
!float.IsNaN(tracking_status.rec_bottom_y))
216+
{
217+
var x = (float)(Math.Min(tracking_status.rec_top_x, tracking_status.rec_bottom_x)) * VideoBox.Image.Width;
218+
var y = (float)(Math.Min(tracking_status.rec_top_y, tracking_status.rec_bottom_y)) * VideoBox.Image.Height;
219+
var w = (float)Math.Abs(tracking_status.rec_top_x - tracking_status.rec_bottom_x) * VideoBox.Image.Width;
220+
var h = (float)Math.Abs(tracking_status.rec_top_y - tracking_status.rec_bottom_y) * VideoBox.Image.Height;
221+
using (var g = Graphics.FromImage(VideoBox.Image))
222+
{
223+
g.DrawRectangle(Pens.Red, x, y, w, h);
224+
}
225+
}
226+
}
227+
178228

179229
old?.Dispose();
180230
}
@@ -537,6 +587,7 @@ private void VideoBox_Click(object sender, EventArgs e)
537587
}
538588
else if ((Control.ModifierKeys, me.Button) == preferences.TrackObjectUnderMouse)
539589
{
590+
selectedCamera?.RequestTrackingMessageInterval(5);
540591
var x = (float)point.Value.x;
541592
var y = (float)point.Value.y;
542593
if (dragStartPoint.HasValue)

0 commit comments

Comments
 (0)