Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 22 additions & 17 deletions Controls/GimbalVideoControl.cs
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ public partial class GimbalVideoControl : UserControl, IMessageFilter
// logger
private static readonly ILog log = LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);

// Uncomment the Console.WriteLine line to enable debug output.
private static void DebugConsoleWrite(string format, params object[] args)
{
// Console.WriteLine(format, args);
}

private GimbalControlSettings preferences = new GimbalControlSettings();

private readonly GStreamer _stream = new GStreamer();
Expand Down Expand Up @@ -433,7 +439,7 @@ private void HandleHeldKeys()
previousPitchRate = pitch;
previousYawRate = yaw;
selectedGimbalManager?.SetRatesCommandAsync(pitch, yaw, yaw_lock, selectedGimbalID);
Console.WriteLine($"Pitch: {pitch}, Yaw: {yaw}");
DebugConsoleWrite("Pitch: {0}, Yaw: {1}", pitch, yaw);
}

float zoom = 0;
Expand All @@ -452,7 +458,7 @@ private void HandleHeldKeys()
{
previousZoomRate = zoom;
selectedCamera?.SetZoomAsync(zoom, CAMERA_ZOOM_TYPE.ZOOM_TYPE_CONTINUOUS);
Console.WriteLine($"Zoom: {zoom}");
DebugConsoleWrite("Zoom: {0}", zoom);
}
}

Expand Down Expand Up @@ -506,7 +512,7 @@ private void HandleKeyPress(Keys key)

private void TakePicture()
{
Console.WriteLine("Take picture");
DebugConsoleWrite("Take picture");
selectedCamera?.TakeSinglePictureAsync();
}

Expand All @@ -515,46 +521,46 @@ private void SetRecording(bool start)
isRecording = start;
if(start)
{
Console.WriteLine("Start recording");
DebugConsoleWrite("Start recording");
selectedCamera?.StartRecordingAsync();
}
else
{
Console.WriteLine("Stop recording");
DebugConsoleWrite("Stop recording");
selectedCamera?.StopRecordingAsync();
}
}

private void SetYawLock(bool locked)
{
string message = locked ? "lock" : "follow";
Console.WriteLine($"Set yaw {message}");
DebugConsoleWrite("Set yaw {0}", message);
yaw_lock = locked;
yawLockToolStripMenuItem.Checked = locked;
selectedGimbalManager?.SetRatesCommandAsync(previousPitchRate, previousYawRate, yaw_lock, selectedGimbalID);
}

private void Retract()
{
Console.WriteLine("Retract");
DebugConsoleWrite("Retract");
selectedGimbalManager?.RetractAsync();
}

private void Neutral()
{
Console.WriteLine("Neutral");
DebugConsoleWrite("Neutral");
selectedGimbalManager?.NeutralAsync();
}

private void PointDown()
{
Console.WriteLine("Point down");
DebugConsoleWrite("Point down");
selectedGimbalManager?.SetAnglesCommandAsync(-90, 0, false, selectedGimbalID);
}

private void Home()
{
Console.WriteLine("Home");
DebugConsoleWrite("Home");
var loc = MainV2.comPort?.MAV?.cs.HomeLocation;
selectedGimbalManager?.SetROILocationAsync(loc.Lat, loc.Lng, loc.Alt, frame: MAV_FRAME.GLOBAL);
}
Expand Down Expand Up @@ -632,8 +638,8 @@ private void VideoBox_Click(object sender, EventArgs e)
return;
}
q = attitude * q;
Console.WriteLine("Attitude: {0:0.0} {1:0.0} {2:0.0}", attitude.get_euler_yaw() * MathHelper.rad2deg, attitude.get_euler_pitch() * MathHelper.rad2deg, attitude.get_euler_roll() * MathHelper.rad2deg);
Console.WriteLine("New: {0:0.0} {1:0.0} {2:0.0}", q.get_euler_yaw() * MathHelper.rad2deg, q.get_euler_pitch() * MathHelper.rad2deg, q.get_euler_roll() * MathHelper.rad2deg);
DebugConsoleWrite("Attitude: {0:0.0} {1:0.0} {2:0.0}", attitude.get_euler_yaw() * MathHelper.rad2deg, attitude.get_euler_pitch() * MathHelper.rad2deg, attitude.get_euler_roll() * MathHelper.rad2deg);
DebugConsoleWrite("New: {0:0.0} {1:0.0} {2:0.0}", q.get_euler_yaw() * MathHelper.rad2deg, q.get_euler_pitch() * MathHelper.rad2deg, q.get_euler_roll() * MathHelper.rad2deg);

selectedGimbalManager?.SetAttitudeAsync(q, yaw_lock, selectedGimbalID);

Expand All @@ -649,7 +655,7 @@ private void VideoBox_Click(object sender, EventArgs e)
}
else if ((Control.ModifierKeys, me.Button) == preferences.TrackObjectUnderMouse)
{
selectedCamera?.RequestTrackingMessageInterval(5);
selectedCamera?.SubscribeTracking(5);
var x = (float)point.Value.x;
var y = (float)point.Value.y;
if (dragStartPoint.HasValue)
Expand Down Expand Up @@ -766,10 +772,9 @@ private void AutoConnectTimerCallback(object sender, System.Timers.ElapsedEventA
{
if (CameraProtocol.VideoStreams.Count < 1)
{
Console.Write("Requesting camera information...");
// We must not have any reported video streams. Try to request them
selectedCamera?.RequestCameraInformationAsync().Wait();
Console.WriteLine(" done.");
// We must not have any reported video streams. Try to request them.
selectedCamera?.RequestVideoStreamInformation();
DebugConsoleWrite("Requested video stream information");
// Come back later and see if any streams have been reported
AutoConnectTimer.Start();
return;
Expand Down
3 changes: 1 addition & 2 deletions ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4526,8 +4526,7 @@ public void UpdateCurrentSettings(Action<CurrentState> bs, bool updatenow,
mavinterface.requestDatastream(MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MAV.cs.raterc,
MAV.sysid,
MAV.compid); // request rc info
MAV.Camera?.RequestMessageIntervals(MAV.cs.ratestatus); // use ratestatus until we create a new setting for this
MAV.GimbalManager?.Discover();
MAV.Camera?.UpdateRateIfChanged(MAV.cs.ratestatus); // use ratestatus until we create a new setting for this
}
catch
{
Expand Down
Loading
Loading