public void startslcan(byte canport) { but_slcanmode1.Enabled = false; but_slcanmode2.Enabled = false; try { if (MainV2.comPort.BaseStream.IsOpen) { var cport = MainV2.comPort.MAV.param["CAN_SLCAN_CPORT"].Value; MainV2.comPort.setParam("CAN_SLCAN_CPORT", canport, true); if (cport == 0) { CustomMessageBox.Show("Reboot required" + " after setting CPORT. Please reboot!", Strings.ERROR); return; } MainV2.comPort.setParam("CAN_SLCAN_TIMOUT", 2, true); MainV2.comPort.setParam("CAN_P" + canport + "_DRIVER", 1); MainV2.comPort.setParam("CAN_SLCAN_SERNUM", 0, true); // usb } } catch { } { // grab the connected port var port = MainV2.comPort.BaseStream; // place an invalid port in its place MainV2.comPort.BaseStream = new Comms.SerialPort() { PortName = port.PortName, BaudRate = port.BaudRate }; //check if we started from within mavlink - if not get settings from menu and create port if (!port.IsOpen) { port = new Comms.SerialPort() { PortName = MainV2._connectionControl.CMB_serialport.Text, BaudRate = int.Parse(MainV2._connectionControl.CMB_baudrate.Text) }; } can.SourceNode = 127; can.NodeAdded += (id, msg) => { this.BeginInvoke((Action) delegate { allnodes.Add(new UAVCANModel() { ID = id, Name = "?", Health = msg.health.ToString(), Mode = msg.mode.ToString(), Uptime = TimeSpan.FromSeconds(msg.uptime_sec) }); }); }; if (!port.IsOpen) { port.Open(); } if (chk_log.Checked) { can.LogFile = Settings.Instance.LogDir + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".can"; } can.StartSLCAN(port.BaseStream); can.SetupFileServer(); can.SetupDynamicNodeAllocator(); can.MessageReceived += (frame, msg, transferID) => { if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_NodeStatus)) { var ns = msg as UAVCAN.uavcan.uavcan_protocol_NodeStatus; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); if (nodes.Count() > 0 && nodes.First().Name == "?") { var statetracking = new UAVCAN.uavcan.statetracking(); // get node info UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req gnireq = new UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req() { }; gnireq.encode(UAVCAN.uavcan.uavcan_transmit_chunk_handler, statetracking); var slcan = can.PackageMessage(frame.SourceNode, 30, 0, gnireq); can.WriteToStream(slcan); } foreach (var item in nodes) { switch (ns.health) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK: item.Health = "OK"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING: item.Health = "WARNING"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR: item.Health = "ERROR"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL: item.Health = "CRITICAL"; break; } switch (ns.mode) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL: item.Mode = "OPERATIONAL"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION: item.Mode = "INITIALIZATION"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE: item.Mode = "MAINTENANCE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE: item.Mode = "SOFTWARE_UPDATE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE: item.Mode = "OFFLINE"; break; } item.Uptime = TimeSpan.FromSeconds(ns.uptime_sec); } this.BeginInvoke((Action) delegate { uAVCANModelBindingSource.ResetBindings(false); }); } else if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res)) { var gnires = msg as UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); foreach (var item in nodes) { item.Name = ASCIIEncoding.ASCII.GetString(gnires.name, 0, gnires.name_len); item.HardwareVersion = gnires.hardware_version.major + "." + gnires.hardware_version.minor; item.SoftwareVersion = gnires.software_version.major + "." + gnires.software_version.minor + "." + gnires.software_version.vcs_commit.ToString("X"); item.SoftwareCRC = gnires.software_version.image_crc; item.HardwareUID = gnires.hardware_version.unique_id.Select(a => a.ToString("X2")).Aggregate((a, b) => { return(a + " " + b); }); item.RawMsg = gnires; } this.BeginInvoke((Action) delegate { uAVCANModelBindingSource.ResetBindings(false); }); } }; } }
public void startslcan(byte canport) { but_slcanmode1.Enabled = false; but_slcanmode2.Enabled = false; try { if (!MainV2.comPort.BaseStream.IsOpen) { if (CustomMessageBox.Show( "You are not currently connected via mavlink. Please make sure the device is already in slcan mode or this is the slcan serialport.", "SLCAN", CustomMessageBox.MessageBoxButtons.OKCancel) != CustomMessageBox.DialogResult.OK) { return; } } if (MainV2.comPort.BaseStream.IsOpen) { var cport = MainV2.comPort.MAV.param["CAN_SLCAN_CPORT"].Value; MainV2.comPort.setParam((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, "CAN_SLCAN_CPORT", canport, true); if (cport == 0) { CustomMessageBox.Show("Reboot required" + " after setting CPORT. Please reboot!", Strings.ERROR); return; } MainV2.comPort.setParam((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, "CAN_SLCAN_TIMOUT", 2, true); MainV2.comPort.setParam((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, "CAN_P" + canport + "_DRIVER", 1); //MainV2.comPort.setParam((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, "CAN_SLCAN_SERNUM", 0, true); // usb // blind send var paramname = "CAN_SLCAN_SERNUM"; var req = new MAVLink.mavlink_param_set_t { target_system = (byte)MainV2.comPort.sysidcurrent, target_component = (byte)MainV2.comPort.compidcurrent, param_type = (byte)MainV2.comPort .MAVlist[(byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent] .param_types[paramname], param_id = paramname.MakeBytesSize(16) }; MainV2.comPort.sendPacket(req, (byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent); MainV2.comPort.sendPacket(req, (byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent); } } catch { } { // grab the connected port var port = MainV2.comPort.BaseStream; // place an invalid port in its place if (port != null) { MainV2.comPort.BaseStream = new Comms.SerialPort() { PortName = port.PortName, BaudRate = port.BaudRate } } ; //check if we started from within mavlink - if not get settings from menu and create port if (port == null || !port.IsOpen) { port = new Comms.SerialPort() { PortName = MainV2._connectionControl.CMB_serialport.Text, BaudRate = int.Parse(MainV2._connectionControl.CMB_baudrate.Text) }; } if (can == null) { can = new uavcan(); } can.SourceNode = 127; can.NodeAdded += (id, msg) => { this.BeginInvoke((Action) delegate { allnodes.Add(new UAVCANModel() { ID = id, Name = "?", Health = msg.health.ToString(), Mode = msg.mode.ToString(), Uptime = TimeSpan.FromSeconds(msg.uptime_sec), VSC = msg.vendor_specific_status_code }); }); }; if (!port.IsOpen) { try { port.Open(); } catch (Exception e) { CustomMessageBox.Show(Strings.CheckPortSettingsOr); return; } } if (chk_log.Checked) { can.LogFile = Settings.Instance.LogDir + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".can"; } var prd = new ProgressReporterDialogue(); prd.UpdateProgressAndStatus(-1, "Trying to connect"); prd.DoWork += sender => can.StartSLCAN(port.BaseStream); prd.btnCancel.Click += (sender, args) => { prd.doWorkArgs.CancelAcknowledged = true; port.Close(); }; prd.RunBackgroundOperationAsync(); if (prd.doWorkArgs.CancelRequested || prd.doWorkArgs.ErrorMessage != null) { return; } can.SetupFileServer(); can.SetupDynamicNodeAllocator(); can.MessageReceived += (frame, msg, transferID) => { if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_NodeStatus)) { var ns = msg as UAVCAN.uavcan.uavcan_protocol_NodeStatus; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); if (nodes.Count() > 0 && nodes.First().Name == "?") { var statetracking = new UAVCAN.uavcan.statetracking(); // get node info UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req gnireq = new UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req() { }; gnireq.encode(UAVCAN.uavcan.uavcan_transmit_chunk_handler, statetracking); var slcan = can.PackageMessage(frame.SourceNode, 30, 0, gnireq); can.WriteToStream(slcan); } foreach (var item in nodes) { switch (ns.health) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK: item.Health = "OK"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING: item.Health = "WARNING"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR: item.Health = "ERROR"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL: item.Health = "CRITICAL"; break; } switch (ns.mode) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL: item.Mode = "OPERATIONAL"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION: item.Mode = "INITIALIZATION"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE: item.Mode = "MAINTENANCE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE: item.Mode = "SOFTWARE_UPDATE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE: item.Mode = "OFFLINE"; break; } item.Uptime = TimeSpan.FromSeconds(ns.uptime_sec); } _updatePending = true; this.BeginInvoke((Action) delegate { if (_updatePending) { _updatePending = false; uAVCANModelBindingSource.ResetBindings(false); } }); } else if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res)) { var gnires = msg as UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); foreach (var item in nodes) { item.Name = ASCIIEncoding.ASCII.GetString(gnires.name, 0, gnires.name_len); item.HardwareVersion = gnires.hardware_version.major + "." + gnires.hardware_version.minor; item.SoftwareVersion = gnires.software_version.major + "." + gnires.software_version.minor + "." + gnires.software_version.vcs_commit.ToString("X"); item.SoftwareCRC = gnires.software_version.image_crc; item.HardwareUID = gnires.hardware_version.unique_id.Select(a => a.ToString("X2")).Aggregate((a, b) => { return(a + " " + b); }); item.RawMsg = gnires; item.VSC = gnires.status.vendor_specific_status_code; } _updatePending = true; this.BeginInvoke((Action) delegate { if (_updatePending) { _updatePending = false; uAVCANModelBindingSource.ResetBindings(false); } }); } else if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_debug_LogMessage)) { var debug = msg as UAVCAN.uavcan.uavcan_protocol_debug_LogMessage; this.BeginInvoke((Action) delegate() { DGDebug.Rows.Insert(0, new object[] { frame.SourceNode, debug.level.value, ASCIIEncoding.ASCII.GetString(debug.source, 0, debug.source_len), ASCIIEncoding.ASCII.GetString(debug.text, 0, debug.text_len) }); if (DGDebug.Rows.Count > 100) { DGDebug.Rows.RemoveAt(DGDebug.Rows.Count - 1); } }); } }; } } UAVCAN.uavcan can = new UAVCAN.uavcan();
public void startslcan(byte canport) { but_slcanmode1.Enabled = false; but_slcanmode2.Enabled = false; try { MainV2.comPort.setParam("CAN_SLCAN_CPORT", canport, true); MainV2.comPort.setParam("CAN_SLCAN_TIMOUT", 2, true); MainV2.comPort.setParam("CAN_SLCAN_SERNUM", 0, true); // usb } catch { } { // fail is good var port = MainV2.comPort.BaseStream; MainV2.comPort.BaseStream = new Comms.SerialPort() { PortName = port.PortName, BaudRate = port.BaudRate }; can.SourceNode = 127; can.NodeAdded += (id, msg) => { this.BeginInvoke((Action) delegate { allnodes.Add(new UAVCANModel() { ID = id, Name = "?", Health = msg.health.ToString(), Mode = msg.mode.ToString(), Uptime = TimeSpan.FromSeconds(msg.uptime_sec) }); }); }; if (!port.IsOpen) { port.Open(); } can.StartSLCAN(port.BaseStream); can.SetupFileServer(); can.SetupDynamicNodeAllocator(); can.MessageReceived += (frame, msg, transferID) => { if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_NodeStatus)) { var ns = msg as UAVCAN.uavcan.uavcan_protocol_NodeStatus; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); if (nodes.Count() > 0 && nodes.First().Name == "?") { var statetracking = new UAVCAN.uavcan.statetracking(); // get node info UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req gnireq = new UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_req() { }; gnireq.encode(UAVCAN.uavcan.uavcan_transmit_chunk_handler, statetracking); var slcan = can.PackageMessage(frame.SourceNode, 30, 0, gnireq); can.WriteToStream(slcan); } foreach (var item in nodes) { switch (ns.health) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK: item.Health = "OK"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING: item.Health = "WARNING"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR: item.Health = "ERROR"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL: item.Health = "CRITICAL"; break; } switch (ns.mode) { case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL: item.Mode = "OPERATIONAL"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION: item.Mode = "INITIALIZATION"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE: item.Mode = "MAINTENANCE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE: item.Mode = "SOFTWARE_UPDATE"; break; case (byte)UAVCAN.uavcan.UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE: item.Mode = "OFFLINE"; break; } item.Uptime = TimeSpan.FromSeconds(ns.uptime_sec); } this.BeginInvoke((Action) delegate { uAVCANModelBindingSource.ResetBindings(false); }); } else if (msg.GetType() == typeof(UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res)) { var gnires = msg as UAVCAN.uavcan.uavcan_protocol_GetNodeInfo_res; var nodes = allnodes.Where((a) => a.ID == frame.SourceNode); foreach (var item in nodes) { item.Name = ASCIIEncoding.ASCII.GetString(gnires.name, 0, gnires.name_len); item.HardwareVersion = gnires.hardware_version.major + "." + gnires.hardware_version.minor; item.SoftwareVersion = gnires.software_version.major + "." + gnires.software_version.minor + "." + gnires.software_version.vcs_commit; item.SoftwareCRC = gnires.software_version.image_crc; } this.BeginInvoke((Action) delegate { uAVCANModelBindingSource.ResetBindings(false); }); } }; } }