第一講:編寫 一個簡單的程序

本文將較為詳細的闡述如何自己寫一個程序,并且將其添加到編譯腳本中去。

本文所需基礎

  • 多線程編程

第一部分:寫一個自己的程序

  • 在Firmware/src/moudle下,創(chuàng)建一個文件夾,例如名為myFirstMoudle,給他起一個你想要的名字,創(chuàng)建一個新的C語言文件,假定他為myFirstMoudle.cpp
  • 添加main函數(shù)聲明
   __EXPORT int px4_myFirstMoudle_main(int argc, char *argv[]);
  • 實現(xiàn)主函數(shù)
int px4_myFirstMoudle_main(int argc, char *argv[])
{
    PX4_INFO("Hello!");
    return OK;
}

到目前為止,你已經基本完成了一個模塊的編寫,如果說你只是想要實現(xiàn)一些簡單功能的話。

  • 當然我們不滿足與這些,我們要把它寫成一個可以運行在后端的程序
    首先:定義一些要用的常量
static bool thread_should_exit = false;     /**< 線程是否退出 */  
static bool thread_running = false;     /**< 線程是否在運行 */  
static int myFirstMoudle_task;             /**< 線程句柄 */
  • 聲明線程函數(shù)
int px4_myFirstMoudle_thread_main(int argc, char *argv[]); 
  • 聲明命令的用法打印函數(shù)
    注意此函數(shù)申明為了static,那么只在本文件中有效
static void usage(const char *reason);
  • 實現(xiàn)用法函數(shù)
static void  
usage(const char *reason)  
{  
    if (reason) {  
        warnx("%s\n", reason);  
    }  
    warnx("usage: myFirstMoudle {start|stop|status} [-p <additional params>]\n\n");  
}  
  • 改寫咱們剛剛寫的主函數(shù)
int px4_myFirstMoudle_main(int argc, char *argv[])  
{  
    if (argc < 2) {  
        usage("missing command");  
        return 1;  
    }  //檢測命令有效性
   
   //檢測到運行命令
    if (!strcmp(argv[1], "start")) {  
   
        if (thread_running) {  
            warnx("myFirstMoudle already running\n");  
            /* this is not an error */  
            return 0;  
        }  //判斷線程已經在運行
        //如果沒在運行,準備開始運行線程,更改常量,使線程不可以退出
        thread_should_exit = false;  
        //在nuttx系統(tǒng)中創(chuàng)建一個線程 
        myFirstMoudle_task = px4_task_spawn_cmd("myFirstMoudle",  
                         SCHED_DEFAULT,  //調度方式,一般就是這個值
                         SCHED_PRIORITY_DEFAULT,  //這是優(yōu)先級,忘了define了
                         2000,  //這是棧的大小
                         px4_myFirstMoudle_thread_main,  //在此處填入線程函數(shù)
                         (argv) ? (char *const *)&argv[2] : (char *const *)NULL);  
        return 0;  
    }  
   //如果是退出命令
    if (!strcmp(argv[1], "stop")) {  
        thread_should_exit = true;  
        return 0;  
    }  
   //如果是查詢狀態(tài)命令
    if (!strcmp(argv[1], "status")) {  
        if (thread_running) {  
            warnx("\trunning\n");  
   
        } else {  
            warnx("\tnot started\n");  
        }  
   
        return 0;  
    }  
   
    usage("unrecognized command");  
    return 1;  
}  
  • 現(xiàn)在我們可以實現(xiàn)線程函數(shù)了
int px4_myFirstMoudle_thread_main(int argc, char *argv[])  
{  
   
    warnx("[myFirstMoudle] starting\n");  
   /**< 此處可以填入一些啟動之初要執(zhí)行的代碼
    thread_running = true;  
   
    while (!thread_should_exit) {  
        //此處寫循環(huán)執(zhí)行的代碼
        warnx("Hello!\n");  
        sleep(5);  //注意,這種后臺程序必須要延遲,不然比他低優(yōu)先級的任務永遠不會執(zhí)行
    }  
   
    warnx("[myFirstMoudle] exiting.\n");  
   //此處進行任務結束的一些處理
    thread_running = false;  
   
    return 0;  
}  
  • 之后我們把程序加入到系統(tǒng)里
    修改下面的文件
 Firmware/cmake/configs/nuttx_px4fmu-v4_default.cmake

在后面加上
moudles/myFirstMoudle

  • 之后就可以進行編譯運行一下你自己的小程序了

但是到此并沒有結束,你還要一點小事情,建立一個CMakeLists.txt在當前文件夾下
仿照下面的內容寫一個自己的cmake

px4_add_module( MODULE modules__mc_att_control
    MAIN mc_att_control
    STACK_MAIN 1200
    STACK_MAX 3500
    COMPILE_FLAGS
    SRCS 
        mc_att_control_main.cpp 
    DEPENDS 
         circuit_breaker
        conversion
        mathlib ) 
最后編輯于
?著作權歸作者所有,轉載或內容合作請聯(lián)系作者
【社區(qū)內容提示】社區(qū)部分內容疑似由AI輔助生成,瀏覽時請結合常識與多方信息審慎甄別。
平臺聲明:文章內容(如有圖片或視頻亦包括在內)由作者上傳并發(fā)布,文章內容僅代表作者本人觀點,簡書系信息發(fā)布平臺,僅提供信息存儲服務。

相關閱讀更多精彩內容

友情鏈接更多精彩內容