public MAVState() { this.packetspersecond = new double[0x100]; this.packetspersecondbuild = new DateTime[0x100]; this.lastvalidpacket = DateTime.MinValue; this.sysid = 0; this.compid = 0; sendlinkid = (byte)(new Random().Next(256)); signing = false; this.param = new MAVLinkParamList(); this.packets = new Dictionary <uint, MAVLinkMessage>(); this.aptype = 0; this.apname = 0; this.recvpacketcount = 0; this.VersionString = ""; this.SoftwareVersions = ""; this.SerialString = ""; this.FrameString = ""; camerapoints.Clear(); GMapMarkerOverlapCount.Clear(); this.packetslost = 0f; this.packetsnotlost = 0f; this.packetlosttimer = DateTime.MinValue; cs.parent = this; }
public MAVState(MAVLinkInterface mavLinkInterface, byte sysid, byte compid) { this.parent = mavLinkInterface; this.sysid = sysid; this.compid = compid; this.packetspersecond = new Dictionary <uint, double>(); this.packetspersecondbuild = new Dictionary <uint, DateTime>(); this.lastvalidpacket = DateTime.MinValue; sendlinkid = (byte)(new Random().Next(256)); signing = false; this.param = new MAVLinkParamList(); this.packets = new Dictionary <uint, MAVLinkMessage>(); this.aptype = 0; this.apname = 0; this.recvpacketcount = 0; this.VersionString = ""; this.SoftwareVersions = ""; this.SerialString = ""; this.FrameString = ""; if (sysid != 255 && !(compid == 0 && sysid == 0)) // && !parent.logreadmode) { this.Proximity = new Proximity(this); } camerapoints.Clear(); GMapMarkerOverlapCount.Clear(); this.packetslost = 0f; this.packetsnotlost = 0f; this.packetlosttimer = DateTime.MinValue; cs.parent = this; }
public MAVState(LinkInterface LinkInterface, byte sysid, byte compid) { this.parent = LinkInterface; this.sysid = sysid; this.compid = compid; this.packetspersecond = new Dictionary <uint, double>(); this.packetspersecondbuild = new Dictionary <uint, DateTime>(); this.lastvalidpacket = DateTime.MinValue; sendlinkid = (byte)(new Random().Next(256)); //this.param = new MAVLinkParamList(); this.packets = new Dictionary <uint, MAVLinkMessage>(); this.recvpacketcount = 0; this.VersionString = ""; camerapoints.Clear(); GMapMarkerOverlapCount.Clear(); this.packetslost = 0f; this.packetsnotlost = 0f; this.packetlosttimer = DateTime.MinValue; cs.parent = this; }
public MAVState() { this.packetspersecond = new double[0x100]; this.packetspersecondbuild = new DateTime[0x100]; this.lastvalidpacket = DateTime.MinValue; this.sysid = 0; this.compid = 0; this.param = new MAVLinkParamList(); this.packets = new byte[0x100][]; this.packetseencount = new int[0x100]; this.aptype = 0; this.apname = 0; this.recvpacketcount = 0; this.VersionString = ""; this.SoftwareVersions = ""; this.SerialString = ""; this.FrameString = ""; camerapoints.Clear(); GMapMarkerOverlapCount.Clear(); this.packetslost = 0f; this.packetsnotlost = 0f; this.packetlosttimer = DateTime.MinValue; cs.parent = this; }
private void CMB_camera_SelectedIndexChanged(object sender, EventArgs e) { if (cameras.ContainsKey(CMB_camera.Text)) { camerainfo camera = cameras[CMB_camera.Text]; NUM_focallength.Value = (decimal)camera.focallen; TXT_imgheight.Text = camera.imageheight.ToString(); TXT_imgwidth.Text = camera.imagewidth.ToString(); TXT_sensheight.Text = camera.sensorheight.ToString(); TXT_senswidth.Text = camera.sensorwidth.ToString(); //NUM_Distance.Enabled = false; } GMapMarkerOverlap.Clear(); domainUpDown1_ValueChanged(null, null); }