<ruby id="bdb3f"></ruby>

    <p id="bdb3f"><cite id="bdb3f"></cite></p>

      <p id="bdb3f"><cite id="bdb3f"><th id="bdb3f"></th></cite></p><p id="bdb3f"></p>
        <p id="bdb3f"><cite id="bdb3f"></cite></p>

          <pre id="bdb3f"></pre>
          <pre id="bdb3f"><del id="bdb3f"><thead id="bdb3f"></thead></del></pre>

          <ruby id="bdb3f"><mark id="bdb3f"></mark></ruby><ruby id="bdb3f"></ruby>
          <pre id="bdb3f"><pre id="bdb3f"><mark id="bdb3f"></mark></pre></pre><output id="bdb3f"></output><p id="bdb3f"></p><p id="bdb3f"></p>

          <pre id="bdb3f"><del id="bdb3f"><progress id="bdb3f"></progress></del></pre>

                <ruby id="bdb3f"></ruby>

                企業??AI智能體構建引擎,智能編排和調試,一鍵部署,支持知識庫和私有化部署方案 廣告
                # PX4固件調試 # [toc] Ubuntu下Eclipse的安裝參考我的博客; 如何在Eclipse下搭建PX4開發環境參見[一個國外的網站](https://uav-lab.org/2016/07/28/px4-research-log-2-how-to-set-up-px4-development-environment-on-ubuntu/)之第5項; 參考資料: - PX4固件在github上的代碼倉庫:https://github.com/PX4/Firmware; - 我自己在github上的代碼倉庫:郵箱(408513516@qq.com)或用戶名(thrillerqin)登錄; - 我在CSDN上的博客地址:是用我的QQ號登錄的; - git學習參考[廖雪峰的git教程](www.liaoxuefeng.com),通俗易懂; - [PX4串口、主題發布訂閱方面很實用的博客](http://blog.csdn.net/freeape/article/details/47837415),也是我在編寫天騰大氣探測項目是參考的框架; - 串口調試工具:gtkterm,不是很好用,不方便,每次插拔usb串口時需重新配置打開串口,而且配置的方式也不方便,就因為這個導致調試mavlink時耽誤了很長時間; - cutecom,挺好用的串口調試工具,就用這個了以后; - git圖形化工具,我選用了gitkraken,跨平臺的; **大氣探測模塊項目在本地的位置:src/examples/tt_atmos_detect** ### 2017年5月8日 ### v1.5.0上創建atmos_detect分支,用于開發大氣探測無人機; ### 2017年6月6日 ### 由于昨天的失誤,執行make distclean指令后將自己后加的代碼全部清除,所以今天就從頭再來,從git clone開始!!! 1. 從[PX4固件的官方倉庫](https://github.com/PX4/Firmware)fork一份PX4固件到[自己倉庫](https://github.com/thrillerqin),我此時fork的版本是1.6.1,該PX4在[我代碼倉庫的地址](https://github.com/thrillerqin/Firmware),以后我就可以在我的這個代碼倉庫里工作了,不影響官方的PX4倉庫。 1. 從我的PX4 Firmware代碼倉庫clone一份到本地。由于PX4固件包含子模塊(位于別的代碼倉庫里的模塊),在克隆代碼倉庫或checkout特定的版本倉庫后,一定要記得更新相應的子模塊(若代碼倉庫有的話),因為克隆代碼倉庫時不會自動克隆子模塊。須執行git submodule,否則會造成子模塊缺失或和主代碼倉庫不兼容。 關于submodule具體參考網頁: [網頁1](http://blog.csdn.net/wangjia55/article/details/24400501) [網頁2](http://www.tuicool.com/articles/jqiEJzU) 克隆過程如下: ``` mkdir src cd src git clone git@github.com:thrillerqin/Firmware.git cd Firmware git submodule update --init --recursive ``` 1. 準備創建自己的分支,復習下常用的git指令: ``` git status |查看當前的狀態 git tag |列出所有的標簽,這里列出的標簽有v1.4.1,v1.5.0等 git branch |列出所有分支,這里的分支只有master git checkout |切換至相應的分支或者標簽 ``` 克隆代碼以后,checkout到v1.5.0上,并創建atmos_detect分支,用于開發大氣探測無人機,過程如下: 在本地PX4 Firmware目錄下, ``` git status |查看當前的狀態 git tag |列出所有的標簽,這里列出的標簽有v1.4.1,v1.5.0等 git branch |列出所有分支,這里的分支只有master git checkout v1.5.0 |切換至相應的標簽v1.5.0 HEAD detached at v1.5.0 git submodule update --init --recursive qb@qb-Lenovo-XiaoXin-310-15IKB:~/tt_atmos_detect/Firmware$ git branch tt_atmos_detect |創建分支tt_atmos_detect qb@qb-Lenovo-XiaoXin-310-15IKB:~/tt_atmos_detect/Firmware$ git branch |查看分支 * (HEAD detached at v1.5.0) master tt_atmos_detect qb@qb-Lenovo-XiaoXin-310-15IKB:~/tt_atmos_detect/Firmware$ git checkout tt_atmos_detect |切換至分支tt_atmos_detect Switched to branch 'tt_atmos_detect' qb@qb-Lenovo-XiaoXin-310-15IKB:~/tt_atmos_detect/Firmware$ git status |查詢狀態,目前在分支tt_atmos_detect On branch tt_atmos_detect ``` 1. 把該工程導入eclipse,具體過程參考一國外網頁(https://uav-lab.org/2016/07/28/px4-research-log-2-how-to-set-up-px4-development-environment-on-ubuntu/之第5項)。由于PX4原生固件代碼包含了eclipse工程文件,導入過程非常簡單:在源碼文件目錄(如,~/tt_atmos_detect/Firmware),“eclipse.cproject”重命名為“.cproject”, “eclipse.project”重命名為“.project”。 啟動eclipse,創建一個新的工作區,單擊File->Import...在彈出對話框選擇General->Existing Projects into Workspace,單擊next彈出下一個對話框,單擊Select root directory右側的按鈕Browse… ,選擇代碼的目錄單擊Ok. You should see PX4-Firmware in available projects. Select the project and click finish. 到工程界面,build target(px4fmu-v2_default),編譯時出錯,按照出錯提示安裝相應的軟件即可(注意,由于系統配置的不同,需安裝的程序也不同,我之前第一次編譯時就是直接通過的,這期間可能是因為在整mavlink時配置python環境整的),一定要看系統錯誤或提示信息,他有時會給解決方案,以下是這次按錯誤提示信息所做的工作,僅限這次,下次還不一定出什么別的幺蛾子: qb@qb-Lenovo-XiaoXin-310-15IKB:~$ sudo pip install catkin_pkg qb@qb-Lenovo-XiaoXin-310-15IKB:~$ sudo pip install catkin_pkg 重新build target(px4fmu-v2_default),編譯鏈接成功! 在左側工程管理窗口Build Targets右鍵選擇create...新建名為px4fmu-v2_default upload的Target,用于向飛控燒寫程序。 1. 創建用戶自定義消息,并公告發布訂閱主題。 固件中消息位于Firmware/msg/*.msg,可以參考現有消息格式新建自定義消息。在Firmware/msg/下新建文件sensor_atmos.msg,有關大氣主題的消息內容: ``` #天騰大氣傳感器數據項 int8 temperature #溫度,int8 uint8 humidity #濕度,uint8 uint16 O3 uint16 CO uint16 PM2_5 uint16 PM10 uint16 NO2 uint16 SO2 ``` 把在文件名sensor_atmos.msg添加至Firmware/msg/CMakeList.txt build Targets->all(必須選擇all,其它不行),會生成該消息的頭文件Firmware/uORB/sensor_atmos.h ### 編寫一個簡單的hello sky程序 ### 先初始牛刀,添加一個簡單的hello sky程序熟悉下編譯鏈接下載執行的流程,還是參考開發手冊(教程->編寫應用程序): 1. 現有固件代碼中已包含hello sky例程,位于Firmware/src/example/px4_simple_app/,已經有現成的就可以直接用,若要使自己重寫的話,參考example里的格式編寫xx.c和對應的CMakeList.txt文件即可,一定要參考別的程序格式! 2. 有了自己的代碼之后,需要添加到該工程,否則不能被build,腫么添加?因為PX4原生固件工程是由CMake組織管理的,具體怎么管理我也不清除,跟著PX4開發手冊走就行了:Pixhawk v1/2的CMake總工程文件:Firmware/cmake/configs/nuttx_px4fmu-v2_default.cmake,在該文件中參考其它程序添加第一步的源碼文件名,格式參考文件中的其它代碼; 3. Build Targets -> px4fmu-v2_default -> px4fmu-v2_default upload,下載程序,OK!!!在upload程序時若一直uploading沒有進度的話,可以重新插拔下usb接口; 4. 確認Pixhawk沒插SD卡,重啟Pixhawk,進入nsh模式。據本人不準確的信息,v1.5.0和之前的版本支持無sd卡啟動進入nsh模式,之后的版本不支持,若還想之前那樣進入nsh模式需修改啟動文件 >[warning]Firmware/ROMFS/px4fmu_common/init.d/rcS,具體添加什么內容、添加到什么位置參考之前的版本。 5. 怎么登錄Pixhawk的nsh命令終端,在Ubuntu下打開命令行終端,輸入一下命令(通過串口連接至pixhawk串口/dev/ttyACM0,波特率115200,參數8n1): >qb@qb-Lenovo-XiaoXin-310-15IKB:~$ screen /dev/ttyACM0 115200 8n1 回車后進入nsh模式,由于PX4+Pixhawk是基于嵌入式操縱系統nuttx開發的,nuttx類似有點類似linux,所謂nsh就是nuttx shell,在該模式下支持許多類linux的命令,如ls、cd等等。輸入命令help查看nsh支持的指令(按組合鍵ctrl+a+[可以翻屏),包括系統命令和用戶的命令,在這里你會驚喜的發現之前編寫的程序居然成了用戶命令“px4_simple_app”。輸入該命令試試: >nsh> px4_simple_app INFO [px4_simple_app] Hello Sky! WARN [px4_simple_app] [px4_simple_app] Accelerometer: -0.0596 -0.0030 -9.9813 WARN [px4_simple_app] [px4_simple_app] Accelerometer: -0.0810 -0.0107 -9.8812 WARN [px4_simple_app] [px4_simple_app] Accelerometer: -0.0454 0.0130 -9.8755 WARN [px4_simple_app] [px4_simple_app] Accelerometer: -0.0602 0.0118 -9.8558 WARN [px4_simple_app] [px4_simple_app] Accelerometer: -0.0745 0.0102 -9.9096 INFO [px4_simple_app] exiting **居然有反應!!!成功的開始!!!** ### 開始自己的項目 ### 熟悉了PX4開發的基本流程后,開始自己的項目:天騰大氣監測,英文名是tianteng_atmos_detect,這名字是不是很大氣?對,就是這么大氣! 這個項目的架構如下: - 大氣傳感器(via串口) --> PX4飛控板 --> 地面站(via mavlink協議); - 程序負責通過串口讀取大氣傳感器數據,跟新自定義大氣傳感器消息,公告發布基于大氣傳感器消息的主題,發送有關大氣傳感器數據的mavlink消息給地面站 雖然有了以上的一些些基礎,等到要去做一個具體的項目是還是覺得欠的太多,有時間的話可以挑出一個nsh的用戶指令,再找到對應的代碼研究,這樣會逐步熟悉PX4原生固件的架構,掌握整個項目。現在沒時間去這么一步步學習,幸好有度娘,找到了一篇好的csdn博客,PX4串口、主題發布訂閱方面很實用的博客,也是我在[編寫天騰大氣探測項目時參考的框架](http://blog.csdn.net/freeape/article/details/47837415)。 PX4進程間通過uORB通訊,如何公告發布訂閱主題,可以參考開發手冊->中間件及架構->uORB部分。 1. 新建src/modules/tianteng_atmos_detect/tianteng_atmos_detect.c,添加大氣傳感器頭文件: >#include <uORB/topics/sensor_atmos.h> 2. 在此編寫代碼實現串口接受數據并公告發布主題。 3. build并upload之后,在nsh就能顯示該用戶命令了,調試的時候可以這么辦,總不能讓用戶也這么用吧,還是有辦法的。可以把該程序添加到啟動文件Firmware/ROMFS/px4fmu_common/init.d/rcS,在該文件“# End of autostart”之前添加內容:tianteng_atmos_detect start /dev/ttyS6,之所以寫成這個形式請自行分析代碼tianteng_atmos_detect.c。 ### 2017年6月10日 ### 重新實現了讀取串口消息->公告發布消息主題,測試的方式是tianteng_atmos_detect在開機時自動啟動,負責接收串口(SERIAL 4,/dev/ttyS6)消息,并公告發布sensor_atmos主題,px4_simple_app負責訂閱消息,并打印出來,在Ubuntu用的串口調試工具是GtkTerm. #### 發送用戶自定義mavlink消息 #### 根據開發文檔->中間件及架構->自定義MAVLink消息,還有CSDN上[一篇非常有用的FantasyJXF的博客](http://blog.csdn.net/oqqenvy12/article/details/56849572)學習實現。 1. 創建自定義uORB消息msg/custom_messages.msg,build all之后會生成對應的頭文件uORB/custom_messages.h; 1. 在custom_messages.xml中創建自定義MAVLink消息; 1. 使用Python -m mavgenerate打開mavlink消息生成器導入上面的xml文件,生成相應的C文件; 1. 將生成的custom_messages文件夾拖到Firmware/mavlink/include/mavlink/v1.0目錄下; 1. 發送自定義MAVLink消息; 1. 添加mavlink的頭文件和uorb消息到mavlink_messages.cpp; 1. 在mavlink_messages.cpp中創建一個新的類; 1. 附加流類streams_list的到mavlink_messages.cpp底部; 1. 最后在mavlink_main.cpp加入自定義的消息以及期望的更新頻率; 以上寫的這些步驟是在fantasyJXF的博客中摘抄的,描述的具體詳細,經本人實踐沒有問題! 實際調試的時候遇到了問題,PX4接收到串口消息后,發布消息(確認發布成功),按道理應該發送對應的mavlink消息,結果卻在串口調試工具(GTKterm)中沒有發現該消息,就因這個問題折騰了將近一周的時間,總以為是是在以上步驟中哪步有問題,后來發現是串口調試工具(GTKterm)的問題,每次燒寫或開機重啟PX4后須重新設置下這個串口工具,否則不能正常通訊。工欲善其事必先利其器。 #### 接收到的消息,存入SD卡 #### 從串口接收到消息以后存入SD卡,具體參考如下代碼: ``` int tianteng_atmos_detect_thread_main(int argc, char *argv[]) { if (argc < 2) { errx(1, "[YCM]need a serial port name as argument"); usage("eg:"); } const char *uart_name = argv[1]; warnx("[YCM]opening port %s", uart_name); char data = '0'; char buffer[5] = ""; /* * TELEM1 : /dev/ttyS1 * TELEM2 : /dev/ttyS2 * GPS : /dev/ttyS3 * NSH : /dev/ttyS5 * SERIAL4: /dev/ttyS6 * N/A : /dev/ttyS4 * IO DEBUG (RX only):/dev/ttyS0 */ int uart_read = uart_init(uart_name); if(false == uart_read)return -1; if(false == set_uart_baudrate(uart_read,9600)){ printf("[YCM]set_uart_baudrate is failed\n"); return -1; } printf("[YCM]uart init is successful\n"); thread_running = true; /*初始化數據結構體 */ struct sensor_atmos_s sensor_atmos_data; memset(&sensor_atmos_data, 0, sizeof(sensor_atmos_data)); /* 公告主題 */ orb_advert_t sensor_atmos_pub = orb_advertise(ORB_ID(sensor_atmos), &sensor_atmos_data); ///////////////////////////// FILE *fd = NULL; char pname[64]; time_t timeSec = time(NULL);//1970.01.01 struct tm *timeinfo=localtime(&timeSec); sprintf(pname, PX4_ROOTFSDIR"/fs/microsd/TIANTENG(%d_%d_%d).txt", timeinfo->tm_year+1900,timeinfo->tm_mon+1,timeinfo->tm_mday); //sprintf(pname, PX4_ROOTFSDIR"/fs/microsd/TIANTENG.txt"); fd = fopen(pname,"a");// fsync(fileno(fd)); fclose(fd); /* FILE *f = fopen(PX4_ROOTFSDIR"/fs/microsd/inav.log", "a"); if (f) { char *s = malloc(256); unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f] y_est=[%.5f %.5f] z_est=[%.5f %.5f] x_est_prev=[%.5f %.5f] y_est_prev=[%.5f %.5f] z_est_prev=[%.5f %.5f]\n", (unsigned long long)hrt_absolute_time(), msg, (double)dt, (double)x_est[0], (double)x_est[1], (double)y_est[0], (double)y_est[1], (double)z_est[0], (double)z_est[1], (double)x_est_prev[0], (double)x_est_prev[1], (double)y_est_prev[0], (double)y_est_prev[1], (double)z_est_prev[0], (double)z_est_prev[1]); fwrite(s, 1, n, f); n = snprintf(s, 256, "\tacc=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f mocap_pos_corr=[%.5f %.5f %.5f] w_mocap_p=%.5f\n", (double)acc[0], (double)acc[1], (double)acc[2], (double)corr_gps[0][0], (double)corr_gps[1][0], (double)corr_gps[2][0], (double)corr_gps[0][1], (double)corr_gps[1][1], (double)corr_gps[2][1], (double)w_xy_gps_p, (double)w_xy_gps_v, (double)corr_mocap[0][0], (double)corr_mocap[1][0], (double)corr_mocap[2][0], (double)w_mocap_p); fwrite(s, 1, n, f); n = snprintf(s, 256, "\tvision_pos_corr=[%.5f %.5f %.5f] vision_vel_corr=[%.5f %.5f %.5f] w_xy_vision_p=%.5f w_z_vision_p=%.5f w_xy_vision_v=%.5f\n", (double)corr_vision[0][0], (double)corr_vision[1][0], (double)corr_vision[2][0], (double)corr_vision[0][1], (double)corr_vision[1][1], (double)corr_vision[2][1], (double)w_xy_vision_p, (double)w_z_vision_p, (double)w_xy_vision_v); fwrite(s, 1, n, f); free(s); } fsync(fileno(f)); fclose(f); */ ///////////////////////////// while(!thread_should_exit){ read(uart_read,&data,1); if(data == 'R'){ for(int i = 0;i <4;i++){ read(uart_read,&data,1); buffer[i] = data; data = '0'; } //strncpy(sonardata.datastr,buffer,4); //sonardata.data = atoi(sonardata.datastr); sensor_atmos_data.CO = (buffer[0] & 0x0f) * 1000; sensor_atmos_data.CO += (buffer[1] & 0x0f) * 100; sensor_atmos_data.CO += (buffer[2] & 0x0f) * 10; sensor_atmos_data.CO += (buffer[3] & 0x0f); //printf("[YCM]sensor_atmos_data.CO=%d\n", sensor_atmos_data.CO); orb_publish(ORB_ID(sensor_atmos), sensor_atmos_pub, &sensor_atmos_data); write(uart_read,buffer,4); //串口消息回傳用于調試 //存儲數據 fd = fopen(pname,"a");// ///if (!fd){ //(fd != NULL) { timeSec = time(NULL);//1970.01.01 timeinfo=localtime(&timeSec); //fwrite("abcde", 5 , 5, fd); fprintf(fd,"CO:%04d\t", sensor_atmos_data.CO); fprintf(fd,"%d-%d-%d %d:%d:%d \n",timeinfo->tm_year+1900,timeinfo->tm_mon+1,timeinfo->tm_mday,timeinfo->tm_hour+8,timeinfo->tm_min,timeinfo->tm_sec); // fclose(fd); //} fsync(fileno(fd)); fclose(fd); } //PX4_INFO("Hello Sky!");//printf("[YCM]qinbao\n"); //sleep(2); //延時2秒 } //fclose(fd); warnx("[YCM]exiting"); thread_running = false; close(uart_read); fflush(stdout); return 0; } ``` ### 2017年5月14日 ### 暫時放棄tests模塊的調試,先參考tests的代碼先做大氣傳感器調試的工作。 基本的思路是:讀傳感器數據,解析數據,存儲數據,爭取這周能搞定,下周踏實去三亞; pixhawk硬件部分的參考網站:http://www.pixhawk.com/modules/pixhawk ### 2017年5月15日 ### 在查找串口號和對應設備號關系的過程中發現查找官方資料的好的路徑: >[PIX HAWK官網](www.pixhawk.org) -> OVERVIEW -> INDEX 然后在user欄找到WIRING就ok了; ### 2017年5月16日 ### 按照[一篇博客的文章編寫串口相關的程序](http://blog.csdn.net/freeape/article/details/47837415) 在Ubuntu上的串口調試工具: 1. 圖形話調試工具,gtkterm,按命令提示安裝; 2. 在網上找到一個在終端命令行調試的如下: >cat /dev/ttyUSB0 某Makefile片段,代碼: ``` #------------------------------------------ monitor: stty -F /dev/ttyUSB0 9600 cs8 -parenb -cstopb # stty -F /dev/ttyUSB0 5:0:8bd:0:3:1c:7f:15:4:0:1:0:11:13:1a:0:12:f:17:16:0:0:0:0:0:0:0:0:0:0:0:0:0:0:0:0 cat /dev/ttyUSB0 #------------------------------------------ ``` ### 2017年5月18日 ### 前兩天主要是調試了串口,用gtkterm發送一組以0x0d結尾的數據,qb_atmos_detect接收以后,通過串口發送出去,可以通過gtkterm看到; 今天還是在那篇博客的指導下,熟悉訂閱主題、發布主題的流程; ### 2017年5月20日 ### Firmware/msg,新建文件sensor_atmos.msg,用于新建消息; 編譯,Build Targets->all,注意選擇的編譯目標為all,編譯過程中通過genmsg_cpp自動生成相應的頭文件sensor_atmos.h,具體的生成過程在該頭文件中有所描述,是這樣的:Auto-generated by genmsg_cpp from file /home/qb/qinbao_px4_atmos_detect/Firmware/msg/sensor_atmos.msg。 ### 2017年5月21日 ### 今天把發布主題和訂閱主題了,接下來把這個過程記錄下; ``` (argv) ? (char * const *)&argv[2] : (char * const *)NULL); int qb_atmos_detect_thread_main(int argc, char *argv[]) { char sample_test_uart[25] = {'S', 'A', 'M', 'P', 'L', 'E', ' ', '\n'}; PX4_INFO("Hello Sky!"); /* NuttX UART PX4FMUv1 UART PX4FMUv2 (Pixhawk) UART /dev/ttyS0 UART1(NSH console) IO DEBUG (RX only) /dev/ttyS1 UART2 TELEM1 (USART1) /dev/ttyS2 UART5 TELEM2 (USART2) /dev/ttyS3 UART6 GPS (UARTX) /dev/ttyS4 N/A N/A (UART5, IO link) /dev/ttyS5 N/A SERIAL5 (UART7, NSH console do only use as console) /dev/ttyS6 N/A SERIAL4 (UART8) */ int serial_port_fd = uart_init("/dev/ttyS6"); //SERIAL4 (UART8) if(false == serial_port_fd) return -1; if(false == set_uart_baudrate(serial_port_fd, 9600)){ printf("[YCM]set_uart_baudrate is failed\n"); return -1; } printf("[YCM]uart init is successful\n"); /* 訂閱主題sensor_combined */ int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined)); orb_set_interval(sensor_sub_fd, 1000); /* 發布主題(advertise) attitude */ struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); /* 發布主題,天騰大氣檢測傳感器主題 */ struct sensor_atmos_s atmos; memset(&atmos, 0, sizeof(atmos)); orb_advert_t atmos_pub = orb_advertise(ORB_ID(sensor_atmos), &atmos); /* one could wait for multiple topics with this technique, just using one here */ px4_pollfd_struct_t fds[] = { { .fd = sensor_sub_fd, .events = POLLIN }, /* there could be more file descriptors here, in the form like: * { .fd = other_sub_fd, .events = POLLIN }, */ }; int error_counter = 0; for (int i = 0; i < 50; i++) { //qinbao 50 /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */ int poll_ret = px4_poll(fds, 1, 1000); /* handle the poll result */ if (poll_ret == 0) { /* this means none of our providers is giving us data */ PX4_ERR("[px4_simple_app] Got no data within a second"); } else if (poll_ret < 0) { /* this is seriously bad - should be an emergency */ if (error_counter < 10 || error_counter % 50 == 0) { /* use a counter to prevent flooding (and slowing us down) */ PX4_ERR("[px4_simple_app] ERROR return value from poll(): %d" , poll_ret); } error_counter++; } else { if (fds[0].revents & POLLIN) { /* obtained data for the first file descriptor */ struct sensor_combined_s raw; /* copy sensors raw data into local buffer */ orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw); PX4_WARN("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f", (double)raw.accelerometer_m_s2[0], (double)raw.accelerometer_m_s2[1], (double)raw.accelerometer_m_s2[2]); /* set att and publish this information for other apps */ att.roll = raw.accelerometer_m_s2[0]; att.pitch = raw.accelerometer_m_s2[1]; att.yaw = raw.accelerometer_m_s2[2]; orb_publish(ORB_ID(vehicle_attitude), att_pub, &att); } //接收到以0x0d結尾的字符串后,?? int nread = 0; int index = 0; char c; do { nread = read(serial_port_fd, &c, 1); if (nread > 0) { //printf("%c", c); sample_test_uart[index++] = c; } } while (c != 0x0d); orb_publish(ORB_ID(sensor_atmos), atmos_pub, &atmos); write(serial_port_fd, sample_test_uart, index);//n); /* there could be more file descriptors here, in the form like: * if (fds[1..n].revents & POLLIN) {} */ } } PX4_INFO("exiting"); return 0; } ``` ### 2017年6月2日 ### 實現采集數據自動存入SD卡的功能,目前發現格式化SD卡之后用能正常讀寫,連續的SD使用就有問題,今天太晚了,明天再說; ``` int tianteng_atmos_detect_thread_main(int argc, char *argv[]) { if (argc < 2) { errx(1, "[YCM]need a serial port name as argument"); usage("eg:"); } const char *uart_name = argv[1]; warnx("[YCM]opening port %s", uart_name); char data = '0'; char buffer[5] = ""; /* * TELEM1 : /dev/ttyS1 * TELEM2 : /dev/ttyS2 * GPS : /dev/ttyS3 * NSH : /dev/ttyS5 * SERIAL4: /dev/ttyS6 * N/A : /dev/ttyS4 * IO DEBUG (RX only):/dev/ttyS0 */ int uart_read = uart_init(uart_name); if(false == uart_read)return -1; if(false == set_uart_baudrate(uart_read,9600)){ printf("[YCM]set_uart_baudrate is failed\n"); return -1; } printf("[YCM]uart init is successful\n"); thread_running = true; /*初始化數據結構體 */ struct sensor_atmos_s sensor_atmos_data; memset(&sensor_atmos_data, 0, sizeof(sensor_atmos_data)); /* 公告主題 */ orb_advert_t sensor_atmos_pub = orb_advertise(ORB_ID(sensor_atmos), &sensor_atmos_data); ///////////////////////////// FILE *fd = NULL; char pname[64]; time_t timeSec = time(NULL);//1970.01.01 struct tm *timeinfo=localtime(&timeSec); sprintf(pname, "/fs/microsd/TIANTENG(%d_%d_%d).txt", timeinfo->tm_year+1900,timeinfo->tm_mon+1,timeinfo->tm_mday); fd = fopen(pname,"a+");// fclose(fd); ///////////////////////////// while(!thread_should_exit){ read(uart_read,&data,1); if(data == 'R'){ for(int i = 0;i <4;i++){ read(uart_read,&data,1); buffer[i] = data; data = '0'; } //strncpy(sonardata.datastr,buffer,4); //sonardata.data = atoi(sonardata.datastr); sensor_atmos_data.CO = (buffer[0] & 0x0f) * 1000; sensor_atmos_data.CO += (buffer[1] & 0x0f) * 100; sensor_atmos_data.CO += (buffer[2] & 0x0f) * 10; sensor_atmos_data.CO += (buffer[3] & 0x0f); //printf("[YCM]sensor_atmos_data.CO=%d\n", sensor_atmos_data.CO); orb_publish(ORB_ID(sensor_atmos), sensor_atmos_pub, &sensor_atmos_data); //存儲數據 fd = fopen(pname,"a+");// timeSec = time(NULL);//1970.01.01 timeinfo=localtime(&timeSec); fprintf(fd,"CO:%04d\t", sensor_atmos_data.CO); fprintf(fd,"%d-%d-%d %d:%d:%d \n",timeinfo->tm_year+1900,timeinfo->tm_mon+1,timeinfo->tm_mday,timeinfo->tm_hour+8,timeinfo->tm_min,timeinfo->tm_sec); fclose(fd); write(uart_read,buffer,4); //串口消息回傳用于調試 } //PX4_INFO("Hello Sky!");//printf("[YCM]qinbao\n"); //sleep(2); //延時2秒 } warnx("[YCM]exiting"); thread_running = false; close(uart_read); fflush(stdout); return 0; } ``` 我安裝的系統是ubuntu10.04。 sd卡插上之后,自動mount了。 所以,第一步,umount。 ``` $sudo -i ``` 輸入自己的密碼取得root權限。 ``` # mount ``` 可以看到最后一行的設備號 ``` /dev/mmcblk0 on /media/60C5-3EC0 type vfat (rw,nosuid,nodev,uhelper=udisks,uid=1000,gid=1000,shortname=mixed,dmask=0077,utf8=1,flush) ``` umount這個sd卡 ``` # umount /dev/mmcblk0 ``` 下面上場的是fdisk工具。 ``` # fdisk /dev/mmcblk0 ``` fdisk命令都是非常簡單的。 >WARNING: DOS-compatible mode is deprecated. It's strongly recommended to switch off the mode (command 'c') and change display units to sectors (command 'u'). Command (m for help): m Command action a toggle a bootable flag b edit bsd disklabel c toggle the dos compatibility flag d delete a partition l list known partition types m print this menu n add a new partition o create a new empty DOS partition table p print the partition table q quit without saving changes s create a new empty Sun disklabel t change a partition's system id u change display/entry units v verify the partition table w write table to disk and exit x extra functionality (experts only) 1. 先P,看看sd卡的分區現狀。 1. 然后d,刪除原分區 1. n,創建分區 >Command (m for help): n Command action e extended p primary partition (1-4) p Partition number (1-4): 1 First cylinder (1-62528, default 1): 1 Last cylinder, +cylinders or +size{K,M,G} (1-62528, default 62528): +1500M t,指定分區類型, Command (m for help): t Selected partition 1 Hex code (type L to list codes): L 0 Empty 24 NEC DOS 81 Minix / old Lin bf Solaris 1 FAT12 39 Plan 9 82 Linux swap / So c1 DRDOS/sec (FAT- 2 XENIX root 3c PartitionMagic 83 Linux c4 DRDOS/sec (FAT- 3 XENIX usr 40 Venix 80286 84 OS/2 hidden C: c6 DRDOS/sec (FAT- 4 FAT16 <32M 41 PPC PReP Boot 85 Linux extended c7 Syrinx 5 Extended 42 SFS 86 NTFS volume set da Non-FS data 6 FAT16 4d QNX4.x 87 NTFS volume set db CP/M / CTOS / . 7 HPFS/NTFS 4e QNX4.x 2nd part 88 Linux plaintext de Dell Utility 8 AIX 4f QNX4.x 3rd part 8e Linux LVM df BootIt 9 AIX bootable 50 OnTrack DM 93 Amoeba e1 DOS access a OS/2 Boot Manag 51 OnTrack DM6 Aux 94 Amoeba BBT e3 DOS R/O b W95 FAT32 52 CP/M 9f BSD/OS e4 SpeedStor c W95 FAT32 (LBA) 53 OnTrack DM6 Aux a0 IBM Thinkpad hi eb BeOS fs e W95 FAT16 (LBA) 54 OnTrackDM6 a5 FreeBSD ee GPT f W95 Ext'd (LBA) 55 EZ-Drive a6 OpenBSD ef EFI (FAT-12/16/ 10 OPUS 56 Golden Bow a7 NeXTSTEP f0 Linux/PA-RISC b 11 Hidden FAT12 5c Priam Edisk a8 Darwin UFS f1 SpeedStor 12 Compaq diagnost 61 SpeedStor a9 NetBSD f4 SpeedStor 14 Hidden FAT16 <3 63 GNU HURD or Sys ab Darwin boot f2 DOS secondary 16 Hidden FAT16 64 Novell Netware af HFS / HFS+ fb VMware VMFS 17 Hidden HPFS/NTF 65 Novell Netware b7 BSDI fs fc VMware VMKCORE 18 AST SmartSleep 70 DiskSecure Mult b8 BSDI swap fd Linux raid auto 1b Hidden W95 FAT3 75 PC/IX bb Boot Wizard hid fe LANstep 1c Hidden W95 FAT3 80 Old Minix be Solaris boot ff BBT 1e Hidden W95 FAT1 Hex code (type L to list codes): 6 Changed system type of partition 1 to 6 (FAT16) 這樣就分好了第一個分區,并且指定了分區為fat16。 第二個,我試做分區為linux分區 >Command (m for help): n Command action e extended p primary partition (1-4) p Partition number (1-4): 2 First cylinder (48002-62528, default 48002): Using default value 48002 Last cylinder, +cylinders or +size{K,M,G} (48002-62528, default 62528): Using default value 62528 Command (m for help): t Partition number (1-4): 2 Hex code (type L to list codes): 83 好了,看看成果。 >Command (m for help): p Disk /dev/mmcblk0: 2048 MB, 2048917504 bytes 4 heads, 16 sectors/track, 62528 cylinders Units = cylinders of 64 * 512 = 32768 bytes Sector size (logical/physical): 512 bytes / 512 bytes I/O size (minimum/optimal): 512 bytes / 512 bytes Disk identifier: 0x6f20736b Device Boot Start End Blocks Id System /dev/mmcblk0p1 1 48001 1536024 6 FAT16 /dev/mmcblk0p2 48002 62528 464864 83 Linux 好了,把分區信息寫入磁盤。 Command (m for help): w The partition table has been altered! Calling ioctl() to re-read partition table. WARNING: If you have created or modified any DOS 6.x partitions, please see the fdisk manual page for additional information. Syncing disks. 下面開始格式化。 首先是fat16分區 >#mkdosfs /dev/mmcblk0p1 然后是linux分區 >#mkfs.ext3 /dev/mmcblk0p2 完成之后,取出sd卡,再安裝上去,linux系統已經自動識別了兩個分區,可以用了。 ### 2017年6月3日 ### 大氣數據傳感器程序已經實現了串口接受數據,并發布相關的主題消息,同事通過串口回傳,并記錄至SD卡,具體過程如下: ### 2017年6月4日 ### 今天開始做mavlink消息發送,實現的目的是把采集的傳感器數據通過mavlink消息發送至QGC地面站,并在地面站顯示,具體過程如下: 先去summer培訓群里咨詢了下,也沒有什么正經的回答,靠天靠地靠培訓,不如靠csdn博客。 參考了如下博客: 1. [Mavlink地面站編寫之八–MAVLINK消息自定義](http://blog.csdn.net/gen_ye/article/details/53886586) 2. [Pixhawk原生固件PX4之MAVLink協議解析](http://blog.csdn.net/oqqenvy12/article/details/61615609) 3. 官方相關的[mavlink介紹](http://mavlink.org/messages/common)是最關鍵的 看來看去還是回到了官方的開發文檔,這才是正途。 PX4 Developer Guide->中間件及架構->[MAVLink消息機制](https://dev.px4.io/zh/middleware/mavlink.html) 根據文檔描述過程如下: 1.創建uORB消息,假設你已經在 msg/ca_trajectory.msg 有了一個自定義uORB ca_trajectory 消息; 2.創建mavlink消息。[參考這里](http://qgroundcontrol.org/mavlink/create_new_mavlink_message) >Definition of one Message in XML,Custom Message Definition File >Compiling XML to C/C++ or Python 把XML文件編譯成C/C++文件時出現了問題,正常的話如下三條指令就可以完成: ``` git clone --recursive https://github.com/mavlink/mavlink mavlink-generator cd mavlink-generator/ python mavgenerate.py ``` 正常情況下到此就能啟動mavlink generator,天不遂人愿,未果,咋辦? 參考[mavlink generator的github倉庫](https://github.com/mavlink/mavlink),按照其Installation指導在克隆是增加"--recursive", 添加本地倉庫目錄到PYTHONPATH,export PYTHONPATH=$PYTHONPATH:/home/qb/mavlink-generator 查看是否設置成功,輸入如下指令 >xx@yyy:~/mavlink-generator$ echo $PYTHONPATH :/home/qb/mavlink-generator 官方要求Python2.7+,查看python的版本如下,符合要求: >xx@yyy:~/mavlink-generator$ python --version Python 2.7.12 經過了以上的確認,再次運行python mavgenerate.py,結果出現以下錯誤信息: >Traceback (most recent call last): File "mavgenerate.py", line 42, in <module> from pymavlink.generator import mavgen File "/home/qb/mavlink-generator/pymavlink/generator/mavgen.py", line 12, in <module> from future import standard_library ImportError: No module named future 腫么辦?后來又參考了[國外的一個網站](https://stackoverflow.com/questions/31086530/importerror-no-module-named-concurrent-futures-process)jedema回答說“如果你用Python2.7,必須安裝如下module,pip install futures,Python2.x沒包含futures,Python3.2之后的版本包含了futures”,其實這段回到不是針對我遇到的問題,但是卻提醒了我。接下來就是安裝future,注意沒有s!過程如下: >sudo apt-get install future //用apt-get install指令安裝不行 pip install future //提示pip沒安裝,先安裝pip,sudo apt install python-pip sudo apt install python-pip //安裝python-pip pip install future //安裝pip python mavgenerate.py //運行mavlink generator,成功!!! 以上過程的詳細界面如下: >qb@qb-Lenovo-XiaoXin-310-15IKB:~/mavlink-generator$ sudo apt-get install future Reading package lists... Done Building dependency tree Reading state information... Done E: Unable to locate package future qb@qb-Lenovo-XiaoXin-310-15IKB:~/mavlink-generator$ pip install future The program 'pip' is currently not installed. You can install it by typing: sudo apt install python-pip qb@qb-Lenovo-XiaoXin-310-15IKB:~/mavlink-generator$ sudo apt install python-pip ...安裝OK qb@qb-Lenovo-XiaoXin-310-15IKB:~/mavlink-generator$ pip install future Collecting future Downloading future-0.16.0.tar.gz (824kB) 100% |████████████████████████████████| 829kB 522kB/s Building wheels for collected packages: future Running setup.py bdist_wheel for future ... done Stored in directory: /home/qb/.cache/pip/wheels/c2/50/7c/0d83b4baac4f63ff7a765bd16390d2ab43c93587fac9d6017a Successfully built future Installing collected packages: future Successfully installed future-0.16.0 You are using pip version 8.1.1, however version 9.0.1 is available. You should consider upgrading via the 'pip install --upgrade pip' command. qb@qb-Lenovo-XiaoXin-310-15IKB:~/mavlink-generator$ python mavgenerate.py OK!!! ### 2017年6月5日 ### 本想今天開始整PX4發送mavlink消息,結果在eclipse中執行了make distclean之后,悲催了!!!!!!!!!!!!!!!!!!!!!!!!!!! 這條指令把之前自己寫的代碼給清除了,真的很無語!!!想哭卻哭不出來,重頭再來! 這次做好記錄。 ### 2017年6月16日 ### 凌晨1點,終于能發送mavlink消息的,真的很虐心(由于gtkterm串口調試工具不給力耽誤了將近一周的時間),過程回頭在詳述。發送消息的過程是這樣的: PX4通過串口接收傳感器的參數,公告發布傳感器uORB主題消息,mavlink進程訂閱到該消息后發送一條mavlink消息給地面站。 洗洗睡了! ### 2017年6月22日 ### 存儲功能也加上了,基本的功能包括串口接收->公告發布消息->發送mavlink消息->存儲,已基本完成!!! 小結一下。 ### 2017年6月24日 ### 準備安裝圖形化的git工具,初步選擇GitKraken(官方介紹其為The most popular Git GUI for Windows,Mac AND Linux),下面記錄Ubuntu下安裝過程: 1. 登錄gitkraken官網:https://www.gitkraken.com/ 2. 下載版本為Linux(.deb),(Ubuntu LTS 12.04+,Debian 8+),文件(.deb)是類似windows下的安裝文件,下載雙擊執行安裝即可; 3. CTR+ALT+T,啟動命令行終端,輸入gitkraken即可啟動; *** # 參考文檔 # 1. [px4~summer的博客](http://blog.csdn.net/qq_21842557/article/details/50799636) 2. [fantasyJXF的博客](http://blog.csdn.net/oqqenvy12/article/details/54577063) 3. [Jethro Hazelhurst's Blog (18)](http://diydrones.com/profiles/blog/list?user=1oj2q1uwsuh9z) 4. [Graphics for Wiki Documentation](http://diydrones.com/profiles/blogs/graphics-for-wiki-documentation),無人機的組件示意圖,挺好的; 5. [PX4自定義消息,發布主題,參考fantasy的博客](http://blog.csdn.net/oqqenvy12/article/details/54577063)
                  <ruby id="bdb3f"></ruby>

                  <p id="bdb3f"><cite id="bdb3f"></cite></p>

                    <p id="bdb3f"><cite id="bdb3f"><th id="bdb3f"></th></cite></p><p id="bdb3f"></p>
                      <p id="bdb3f"><cite id="bdb3f"></cite></p>

                        <pre id="bdb3f"></pre>
                        <pre id="bdb3f"><del id="bdb3f"><thead id="bdb3f"></thead></del></pre>

                        <ruby id="bdb3f"><mark id="bdb3f"></mark></ruby><ruby id="bdb3f"></ruby>
                        <pre id="bdb3f"><pre id="bdb3f"><mark id="bdb3f"></mark></pre></pre><output id="bdb3f"></output><p id="bdb3f"></p><p id="bdb3f"></p>

                        <pre id="bdb3f"><del id="bdb3f"><progress id="bdb3f"></progress></del></pre>

                              <ruby id="bdb3f"></ruby>

                              哎呀哎呀视频在线观看