missionplanner編譯修改方法

1.下載工具妇汗,下載visual studio2019 community

進入安裝界面缠诅,安裝界面選擇以下安裝內(nèi)容:.Net桌面開發(fā),使用C++的桌面開發(fā)祭务,通用windows平臺開發(fā),使用.Net的移動開發(fā)圈匆,選擇后一直到安裝完成

2.下載源代碼

方法為:git clone https://github.com/xiaozuozi/MissionPlanner.git

3.打開項目快毛,生成解決方案以及運行

4.編譯成功后進行代碼的修改

下面只進行mavlink通訊相關(guān)的代碼修改格嗅,主要修改的幾個文件為

MAVLinkInterface.cs番挺,CurrentState.cs,MAVLink.cs,MainV2.cs

  • MAVLink.cs
 public const byte MAVLINK_STX = 253;
 public const byte MAVLINK_STX_MAVLINK1 = 0xFE;

其中的MAVLINK_STX是mavlink2.0的幀頭,MAVLINK_STX_MAVLINK1為mavlink1.0的幀頭

  • CurrentState.cs
    此文件是用來修改mavlink的數(shù)據(jù)流的請求頻率的
    在下面的方法中設置頻率
static CurrentState()
        {
            // set default telemrates
            rateattitudebackup = 4;
            ratepositionbackup = 2;
            ratestatusbackup = 2;
            ratesensorsbackup = 2;
            ratercbackup = 2;
            //Init dictionary for storing names for customfields
            custom_field_names = new Dictionary<string, string>();
        }
  • MainV2.cs
public void doConnect(MAVLinkInterface comPort, string portname, string baud, bool getparams = true)

以上方法主要是在點擊連接按鈕的時候屯掖,進行獲取所有參數(shù)等的操作

  • MAVLinkInterface.cs
    所有的mavlink消息的解析在此文件中完成
        public async Task<MAVLinkMessage> readPacketAsync()
        {
            byte[] buffer = new byte[MAVLINK_MAX_PACKET_LEN + 25];
            int count = 0;
            int length = 0;
            int readcount = 0;
            MAVLinkMessage message = null;

            DateTime start = DateTime.Now;

            if (debug)
                Console.WriteLine(DateTime.Now.Millisecond + " SR0 " + BaseStream?.BytesToRead);

            await readlock.WaitAsync().ConfigureAwait(false);
            try
            {
                if (debug)
                    Console.WriteLine(DateTime.Now.Millisecond + " SR1 " + BaseStream?.BytesToRead);

                while ((BaseStream != null && BaseStream.IsOpen) || logreadmode)
                {
                    try
                    {
                        if (readcount > 300)
                        {
                            break;
                        }

                        readcount++;
                        if (logreadmode)
                        {
                            message = readlogPacketMavlink();
                            buffer = message.buffer;
                            if (buffer == null || buffer.Length == 0)
                                return MAVLinkMessage.Invalid;
                        }
                        else
                        {
                            if (BaseStream.ReadTimeout != 1200)
                                BaseStream.ReadTimeout = 1200; // 1200 ms between chars - the gps detection requires this.

                            // time updated for internal reference
                            MAV.cs.datetime = DateTime.Now;

                            DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);

                            if (debug)
                                Console.WriteLine(DateTime.Now.Millisecond + " SR1a " + BaseStream?.BytesToRead);

                            while (BaseStream.IsOpen && BaseStream.BytesToRead <= 0)
                            {
                                if (DateTime.Now > to)
                                {
                                    log.InfoFormat("MAVLINK: 1 wait time out btr {0} len {1}", BaseStream?.BytesToRead,
                                        length);
                                    throw new TimeoutException("Timeout");
                                }

                                await Task.Delay(1).ConfigureAwait(false);
                                if (debug)
                                    Console.WriteLine(DateTime.Now.Millisecond + " SR0b " + BaseStream?.BytesToRead);
                            }

                            if (debug)
                                Console.WriteLine(DateTime.Now.Millisecond + " SR1a " + BaseStream?.BytesToRead);
                            if (BaseStream.IsOpen)
                            {
                                BaseStream.Read(buffer, count, 1);
                                if (rawlogfile != null && rawlogfile.CanWrite)
                                    rawlogfile.WriteByte(buffer[count]);
                            }

                            if (debug)
                                Console.WriteLine(DateTime.Now.Millisecond + " SR1b " + BaseStream?.BytesToRead);
                        }
                    }
                    catch (Exception e)
                    {
                        log.Info("MAVLink readpacket read error: " + e.ToString());
                        break;
                    }

                    // check if looks like a mavlink packet and check for exclusions and write to console
                    if (buffer[0] != 0xfe && buffer[0] != 'U' && buffer[0] != 0xfd)
                    {
                        if (buffer[0] >= 0x20 && buffer[0] <= 127 || buffer[0] == '\n' || buffer[0] == '\r')
                        {
                            // check for line termination
                            if (buffer[0] == '\r' || buffer[0] == '\n')
                            {
                                // check new line is valid
                                if (buildplaintxtline.Length > 3)
                                    plaintxtline = buildplaintxtline;

                                log.Info(plaintxtline);
                                // reset for next line
                                buildplaintxtline = "";
                            }

                            TCPConsole.Write(buffer[0]);
                            Console.Write((char)buffer[0]);
                            buildplaintxtline += (char)buffer[0];
                        }

                        _bytesReceivedSubj.OnNext(1);
                        count = 0;
                        buffer[1] = 0;
                        continue;
                    }

                    // reset count on valid packet
                    readcount = 0;

                    if (debug)
                        Console.WriteLine(DateTime.Now.Millisecond + " SR2 " + BaseStream?.BytesToRead);

                    // check for a header
                    if (buffer[0] == 0xfe || buffer[0] == 0xfd || buffer[0] == 'U')
                    {
                        var mavlinkv2 = buffer[0] == MAVLINK_STX ? true : false;

                        int headerlength = mavlinkv2 ? MAVLINK_CORE_HEADER_LEN : MAVLINK_CORE_HEADER_MAVLINK1_LEN;
                        int headerlengthstx = headerlength + 1;

                        // if we have the header, and no other chars, get the length and packet identifiers
                        if (count == 0 && !logreadmode)
                        {
                            DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);

                            while (BaseStream.IsOpen && BaseStream.BytesToRead < headerlength)
                            {
                                if (DateTime.Now > to)
                                {
                                    log.InfoFormat("MAVLINK: 2 wait time out btr {0} len {1}", BaseStream.BytesToRead,
                                        length);
                                    throw new TimeoutException("Timeout");
                                }

                                await Task.Delay(1).ConfigureAwait(false);
                            }

                            int read = BaseStream.Read(buffer, 1, headerlength);
                            count = read;
                            if (rawlogfile != null && rawlogfile.CanWrite)
                                rawlogfile.Write(buffer, 1, read);
                        }

                        // packet length
                        if (buffer[0] == MAVLINK_STX)
                        {
                            length = buffer[1] + headerlengthstx +
                                     MAVLINK_NUM_CHECKSUM_BYTES; // data + header + checksum - magic - length
                            if ((buffer[2] & MAVLINK_IFLAG_SIGNED) > 0)
                            {
                                length += MAVLINK_SIGNATURE_BLOCK_LEN;
                            }
                        }
                        else
                        {
                            length = buffer[1] + headerlengthstx +
                                     MAVLINK_NUM_CHECKSUM_BYTES; // data + header + checksum - U - length    
                        }

                        if (count >= headerlength || logreadmode)
                        {
                            try
                            {
                                if (logreadmode)
                                {
                                }
                                else
                                {
                                    DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);

                                    while (BaseStream.IsOpen && BaseStream.BytesToRead < (length - (headerlengthstx)))
                                    {
                                        if (DateTime.Now > to)
                                        {
                                            log.InfoFormat("MAVLINK: 3 wait time out btr {0} len {1}",
                                                BaseStream.BytesToRead, length);
                                            break;
                                        }

                                        await Task.Delay(1).ConfigureAwait(false);
                                    }

                                    if (BaseStream.IsOpen)
                                    {
                                        int read = BaseStream.Read(buffer, headerlengthstx, length - (headerlengthstx));
                                        if (read != (length - headerlengthstx))
                                            log.InfoFormat("MAVLINK: bad read {0}, {1}, {2}", headerlengthstx, length,
                                                count);
                                        if (rawlogfile != null && rawlogfile.CanWrite)
                                        {
                                            // write only what we read, temp is the whole packet, so 6-end
                                            rawlogfile.Write(buffer, headerlengthstx, read);
                                        }
                                    }
                                }

                                count = length;
                            }
                            catch
                            {
                                break;
                            }

                            break;
                        }
                    }

                    count++;
                    if (count == 299)
                        break;
                }

                if (debug)
                    Console.WriteLine(DateTime.Now.Millisecond + " SR3 " + BaseStream?.BytesToRead);
            } // end readlock
            finally
            {
                readlock.Release();
            }

            // resize the packet to the correct length
            Array.Resize<byte>(ref buffer, count);

            // add byte count
            _bytesReceivedSubj.OnNext(buffer.Length);

            // update bps statistics
            if (_bpstime.Second != DateTime.Now.Second)
            {
                long btr = 0;
                if (BaseStream != null && BaseStream.IsOpen)
                {
                    btr = BaseStream.BytesToRead;
                }
                else if (logreadmode)
                {
                    btr = logplaybackfile.BaseStream.Length - logplaybackfile.BaseStream.Position;
                }

                Console.Write(
                    "bps {0} loss {1} left {2} mem {3} mav2 {4} sign {5} mav1 {6} mav2 {7} signed {8}      \n", _bps1,
                    MAV.synclost, btr,
                    GC.GetTotalMemory(false) / 1024 / 1024.0, MAV.mavlinkv2, MAV.signing, _mavlink1count,
                    _mavlink2count, _mavlink2signed);
                _bps2 = _bps1; // prev sec
                _bps1 = 0; // current sec
                _bpstime = DateTime.Now;
                _mavlink1count = 0;
                _mavlink2count = 0;
                _mavlink2signed = 0;
            }

            _bps1 += buffer.Length;

            if (buffer.Length == 0)
                return MAVLinkMessage.Invalid;

            if (message == null)
                message = new MAVLinkMessage(buffer, DateTime.UtcNow);

            uint msgid = message.msgid;

            message_info msginfo = MAVLINK_MESSAGE_INFOS.GetMessageInfo(msgid);

            // calc crc
            var sigsize = (message.sig != null) ? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
            ushort crc = MavlinkCRC.crc_calculate(buffer, message.Length - sigsize - MAVLINK_NUM_CHECKSUM_BYTES);

            // calc extra bit of crc for mavlink 1.0/2.0
            if (message.header == 0xfe || message.header == 0xfd)
            {
                crc = MavlinkCRC.crc_accumulate(msginfo.crc, crc);
            }

            // check message length size vs table (mavlink1 explicit size check | mavlink2 allow all, undersize 0 trimmed, and oversize unknown extension)
            if (!message.ismavlink2 && message.payloadlength != msginfo.minlength)
            {
                if (msginfo.length == 0) // pass for unknown packets
                {
                    log.InfoFormat("unknown packet type {0}", message.msgid);
                }
                else
                {
                    log.InfoFormat("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", buffer.Length, message.msgid);
                    return MAVLinkMessage.Invalid;
                }
            }

            // check crc
            if ((message.crc16 >> 8) != (crc >> 8) ||
                (message.crc16 & 0xff) != (crc & 0xff))
            {
                if (buffer.Length > 5 && msginfo.name != null)
                    log.InfoFormat("Mavlink Bad Packet (crc fail) len {0} crc {1} vs {4} pkno {2} {3}", buffer.Length,
                        crc, message.msgid, msginfo.name.ToString(),
                        message.crc16);
                if (logreadmode)
                    log.InfoFormat("bad packet pos {0} ", logplaybackfile.BaseStream.Position);
                return MAVLinkMessage.Invalid;
            }

上述代碼中BaseStream.Read(buffer, count, 1);的意思是填入第一個字節(jié)的內(nèi)容玄柏,用來判斷是mavlink1.0還是mavlink2.0,
int read = BaseStream.Read(buffer, 1, headerlength);是填入第1位到payload前一位的所有字節(jié)。int read = BaseStream.Read(buffer, headerlengthstx, length - (headerlengthstx));是填入payload部分和2位crc校驗的值的內(nèi)容贴铜。如果要對mavlink協(xié)議進行解密的話粪摘,則將BaseStream.Read(buffer, count, 1);單獨解密,用來判斷幀頭绍坝,int read = BaseStream.Read(buffer, 2, length -2);是用來獲取后面所有位的值
BaseStream.Write(packet, 0, i);則是發(fā)送指令徘意。其中的0xfe為mavlink1.0的幀頭,0xfd為mavlink2.0的幀頭轩褐。

?著作權(quán)歸作者所有,轉(zhuǎn)載或內(nèi)容合作請聯(lián)系作者
  • 序言:七十年代末椎咧,一起剝皮案震驚了整個濱河市,隨后出現(xiàn)的幾起案子把介,更是在濱河造成了極大的恐慌勤讽,老刑警劉巖,帶你破解...
    沈念sama閱讀 206,968評論 6 482
  • 序言:濱河連續(xù)發(fā)生了三起死亡事件拗踢,死亡現(xiàn)場離奇詭異脚牍,居然都是意外死亡,警方通過查閱死者的電腦和手機巢墅,發(fā)現(xiàn)死者居然都...
    沈念sama閱讀 88,601評論 2 382
  • 文/潘曉璐 我一進店門莫矗,熙熙樓的掌柜王于貴愁眉苦臉地迎上來,“玉大人砂缩,你說我怎么就攤上這事∪洌” “怎么了庵芭?”我有些...
    開封第一講書人閱讀 153,220評論 0 344
  • 文/不壞的土叔 我叫張陵,是天一觀的道長雀监。 經(jīng)常有香客問我双吆,道長,這世上最難降的妖魔是什么会前? 我笑而不...
    開封第一講書人閱讀 55,416評論 1 279
  • 正文 為了忘掉前任好乐,我火速辦了婚禮,結(jié)果婚禮上瓦宜,老公的妹妹穿的比我還像新娘蔚万。我一直安慰自己,他們只是感情好临庇,可當我...
    茶點故事閱讀 64,425評論 5 374
  • 文/花漫 我一把揭開白布反璃。 她就那樣靜靜地躺著昵慌,像睡著了一般。 火紅的嫁衣襯著肌膚如雪淮蜈。 梳的紋絲不亂的頭發(fā)上斋攀,一...
    開封第一講書人閱讀 49,144評論 1 285
  • 那天,我揣著相機與錄音梧田,去河邊找鬼淳蔼。 笑死,一個胖子當著我的面吹牛裁眯,可吹牛的內(nèi)容都是我干的鹉梨。 我是一名探鬼主播,決...
    沈念sama閱讀 38,432評論 3 401
  • 文/蒼蘭香墨 我猛地睜開眼未状,長吁一口氣:“原來是場噩夢啊……” “哼俯画!你這毒婦竟也來了?” 一聲冷哼從身側(cè)響起司草,我...
    開封第一講書人閱讀 37,088評論 0 261
  • 序言:老撾萬榮一對情侶失蹤艰垂,失蹤者是張志新(化名)和其女友劉穎,沒想到半個月后埋虹,有當?shù)厝嗽跇淞掷锇l(fā)現(xiàn)了一具尸體猜憎,經(jīng)...
    沈念sama閱讀 43,586評論 1 300
  • 正文 獨居荒郊野嶺守林人離奇死亡,尸身上長有42處帶血的膿包…… 初始之章·張勛 以下內(nèi)容為張勛視角 年9月15日...
    茶點故事閱讀 36,028評論 2 325
  • 正文 我和宋清朗相戀三年搔课,在試婚紗的時候發(fā)現(xiàn)自己被綠了胰柑。 大學時的朋友給我發(fā)了我未婚夫和他白月光在一起吃飯的照片。...
    茶點故事閱讀 38,137評論 1 334
  • 序言:一個原本活蹦亂跳的男人離奇死亡爬泥,死狀恐怖柬讨,靈堂內(nèi)的尸體忽然破棺而出,到底是詐尸還是另有隱情袍啡,我是刑警寧澤踩官,帶...
    沈念sama閱讀 33,783評論 4 324
  • 正文 年R本政府宣布,位于F島的核電站境输,受9級特大地震影響蔗牡,放射性物質(zhì)發(fā)生泄漏。R本人自食惡果不足惜嗅剖,卻給世界環(huán)境...
    茶點故事閱讀 39,343評論 3 307
  • 文/蒙蒙 一辩越、第九天 我趴在偏房一處隱蔽的房頂上張望。 院中可真熱鬧信粮,春花似錦黔攒、人聲如沸。這莊子的主人今日做“春日...
    開封第一講書人閱讀 30,333評論 0 19
  • 文/蒼蘭香墨 我抬頭看了看天上的太陽莲绰。三九已至,卻和暖如春姑丑,著一層夾襖步出監(jiān)牢的瞬間蛤签,已是汗流浹背。 一陣腳步聲響...
    開封第一講書人閱讀 31,559評論 1 262
  • 我被黑心中介騙來泰國打工栅哀, 沒想到剛下飛機就差點兒被人妖公主榨干…… 1. 我叫王不留震肮,地道東北人。 一個月前我還...
    沈念sama閱讀 45,595評論 2 355
  • 正文 我出身青樓留拾,卻偏偏與公主長得像戳晌,于是被迫代替她去往敵國和親。 傳聞我的和親對象是個殘疾皇子痴柔,可洞房花燭夜當晚...
    茶點故事閱讀 42,901評論 2 345