PX4串口添加传感器—PX4添加自定义mavlik消息

2023-05-16

目录

1——建立.xml并生成mavlink自定义消息文件

1.1.打开终端克隆MAVLINK生成器

1.2.进入克隆目录,执行以下命令

1.3.随手建立储存文件夹

1.4.创建read_uart_sensor.xml文件

1.5.打开MAVLINK Generator生成器

1.6.生成文件自定义MAVLINK消息文件

2——修改PX4的文件(添加自定义消息所需相关设置)

2.1.放置自定义MAVLINK消息文件

2.2.创建read_uart_sensor.msg

2.3.将创建的.msg添加到编译目录

 2.4.修改common.h文件的内容

2.5.修改mavlink_messages.cpp的内容

 2.6.修改mavlink_main.cpp的内容

 3——添加串口读程序以及uorb发送

3.1.创建read_uart_sensor文件夹以及相关文件

3.2.添加CMakeLists.txt编译脚本内容

 3.3.添加串口读取程序read_uart_sensor.c内容

3.4.到对应机型中添加编译文件路径

3.5.创建READ_UART_SENSOR.hpp

4——功能:设置uorb自启动

 5——功能:打印串口消息,到MAVLINK终端

5.1.创建文件夹px4_test及其文件

 5.2.添加CMakeLists.txt内容

5.3.添加 px4_test.c内容

 6——编译调试

6.1.编译固件

6.2.下载固件

6.3.测试显示情况


学无止境,不进则退。

这个项目对于我来说很难,我和好友一起搞了许久才搞好,参考了许多大佬的文章才整理出来了的。

大佬链接:(28条消息) PX4实战之旅(二):通过自定义mavlink消息和QGC通信_老王机器人的博客-CSDN博客

(28条消息) PX4飞控读取UART串口信息通过Mavlink传给QGC地面站显示_XXX_UUU_XXX的博客-CSDN博客_飞控串口协议

(28条消息) PX4读取串口消息,并通过MAVLINK发送给地面站_WENLAISIJEI的博客-CSDN博客

望君参考之余,先赏个赞!!谢谢!!

1——建立.xml并生成mavlink自定义消息文件

1.1.打开终端克隆MAVLINK生成器

git clone https://github.com/mavlink/mavlink.git

1.2.进入克隆目录,执行以下命令

git submodule update --init --recursive
sudo apt-get install python3-tk
sudo pip3 install future

1.3.随手建立储存文件夹

所有的所有路径要英文

1.4.创建read_uart_sensor.xml文件

 其内容(因为我的是两个拉力传感器,其数据是4位的,所以选用了float):

<?xml version="1.0"?>
<!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
<mavlink>
  <version>3</version>
  <messages>
    <message id="166" name="READ_UART_SENSOR">
      <description>READ_UART_SENSOR</description>
      <field type="uint64_t" name="timestamp">Timestamp in milliseconds since system boot</field>
      <field type="float" name="data">float</field>
      <field type="float" name="data1">float</field>
    </message>
  </messages>
</mavlink>

1.5.打开MAVLINK Generator生成器

 来到上面这个页面下,在终端执行下面的指令,从而打开MAVLINK Generator生成器

python3 -m mavgenerate

1.6.生成文件自定义MAVLINK消息文件

 会弹出一个框,选OK就好。下面是生成的内容。

这个文件就是我们要的MAVLINK库文件

 

2——修改PX4的文件(添加自定义消息所需相关设置)

2.1.放置自定义MAVLINK消息文件

把上面生成的文件放到此路径下,如下图:

2.2.创建read_uart_sensor.msg

所在位置及其内容,瞅瞅下图:

uint64 timestamp		# time since system start (microseconds)
char[10] datastr
char[10] data1str
float32 data
float32 data1
 
# TOPICS read_uart_sensor   

2.3.将创建的.msg添加到编译目录

瞅瞅下图:

 2.4.修改common.h文件的内容

对应位置放:

#include "./mavlink_msg_read_uart_sensor.h"

MAVLINK_MESSAGE_INFO_READ_UART_SENSOR, 

注:在我们之前的实验中,一开始用的是ID223,但是没有效果。。多次实验后,选用166就得行了。目前没找到原因,也许是我们没有做尝试更多的ID。虽然有QGC有ID166,但是我们换取内容后ID166是不会影响飞控的,

{ "REAR_UART_SENSOR", 166 }, 

复制下面文件的这段代码。我的是这个哈,你们的我就不晓得,要看你们文件里的是啥

 {166, 218, 16, 16, 0, 0, 0}, 

 添加到这里(这里是第27行的数组#define MAVLINK_MESSAGE_CRCS):

2.5.修改mavlink_messages.cpp的内容

注:时刻区分大小写

#include "streams/READ_UART_SENSOR.hpp"

注:学会仿照添加

#if defined(READ_UART_SENSOR_HPP)
	create_stream_list_item<MavlinkStreamReadUartSensor>(),
#endif // READ_UART_SENSOR_HPP

 2.6.修改mavlink_main.cpp的内容

设置发送频率(MHZ),同时设置发送方式,我们这里直接放在switch语句的最后面,就可以不用管发送方式了:

		configure_stream_local("READ_UART_SENSOR", 20.0f);

 3——添加串口读程序以及uorb发送

3.1.创建read_uart_sensor文件夹以及相关文件

3.2.添加CMakeLists.txt编译脚本内容

简单理解就是告诉编译器,记得把resd_uart_sensor.c文件给编译哈

set(MODULE_CFLAGS)
px4_add_module(
        MODULE modules_read_uart_sensor
        MAIN read_uart_sensor
    COMPILE_FLAGS
        -Os
    SRCS
        read_uart_sensor.c
        
    DEPENDS
)

 3.3.添加串口读取程序read_uart_sensor.c内容

这里面是精华:如果你要换文件,那么改的东西会不少哦。(具体的参考最上面的链接,那都是大佬)

/*
 * read_uart_sensor.c
 *
 * read sensor through uart
 */

#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include <string.h>
#include <systemlib/err.h>
//#include <systemlib/systemlib.h>
#include <fcntl.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <px4_platform_common/tasks.h>
#include <uORB/topics/read_uart_sensor.h>

__EXPORT int read_uart_sensor_main(int argc, char *argv[]);


static bool thread_should_exit = false; /*Ddemon exit flag*/
static bool thread_running = false;  /*Daemon status flag*/
static int daemon_task;

/**
 * Main loop
 */
int read_uart_thread_main(int argc, char *argv[]);

static int uart_init(const char * uart_name);
static int set_uart_baudrate(const int fd, unsigned int baud);
static void usage(const char *reason);

int set_uart_baudrate(const int fd, unsigned int baud)
{
    int speed;

    switch (baud) {
        case 9600:   speed = B9600;   break;
        case 19200:  speed = B19200;  break;
        case 38400:  speed = B38400;  break;
        case 57600:  speed = B57600;  break;
        case 115200: speed = B115200; break;
        default:
            warnx("ERR: baudrate: %d\n", baud);
            return -EINVAL;
    }

    struct termios uart_config;

    int termios_state;
    /* 以新的配置填充结构体 */
    /* 设置某个选项,那么就使用"|="运算,
     * 如果关闭某个选项就使用"&="和"~"运算
     * */

    /* fill the struct for the new configuration */
    tcgetattr(fd, &uart_config);// 获取终端参数
    /* clear ONLCR flag (which appends a CR for every LF) */
    uart_config.c_oflag &= ~ONLCR;// 将NL转换成CR(回车)-NL后输出
    /* no parity, one stop bit */
    /* 无偶校验,一个停止位 */

    uart_config.c_cflag &= ~(CSTOPB | PARENB);// CSTOPB 使用两个停止位,PARENB 表示偶校验
    /* set baud rate */

     /* 设置波特率 */
    if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
        warnx("ERR: %d (cfsetispeed)\n", termios_state);
        return false;
    }

    if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
        warnx("ERR: %d (cfsetospeed)\n", termios_state);
        return false;
    }

    // 设置与终端相关的参数,TCSANOW 立即改变参数
    if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
        warnx("ERR: %d (tcsetattr)\n", termios_state);
        return false;
    }

    return true;
}


int uart_init(const char * uart_name)
{
    int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);
     /*Linux中,万物皆文件,打开串口设备和打开普通文件一样,使用的是open()系统调用*/
    // 选项 O_NOCTTY 表示不能把本串口当成控制终端,否则用户的键盘输入信息将影响程序的执行

    if (serial_fd < 0) {
        err(1, "failed to open port: %s", uart_name);
        return false;
    }
    return serial_fd;
}


//进程提示函数,用来提示可输入的操作
static void usage(const char *reason)
{
    if (reason) {
        fprintf(stderr, "%s\n", reason);
    }

    fprintf(stderr, "usage: read_uart_sensor {start|stop|status} [param]\n\n");
    exit(1);
}


//主函数入口
int read_uart_sensor_main(int argc, char *argv[])
{
    if (argc < 2) {
        usage("[Fantasy]missing command");
    }
 //输入为start
    if (!strcmp(argv[1], "start")) {
        if (thread_running) {//进程在运行
            warnx("[Fantasy]already running\n");//打印提示已经在运行
            return 0;;//跳出代码
        }
         //如果是第一次运行
        thread_should_exit = false;//定义一个守护进程
        //建立名为read_uart_sensor进程SCHED_PRIORITY_MAX - 55,
        daemon_task = px4_task_spawn_cmd("read_uart_sensor",
                         SCHED_DEFAULT,
                         SCHED_PRIORITY_DEFAULT,//调度优先级
                           //SCHED_PRIORITY_MAX - 1,
                         2000,//堆栈分配大小
                         read_uart_thread_main,
                         (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
        return 0;
    }

    if (!strcmp(argv[1], "stop")) {
        thread_should_exit = true;//进程标志变量置true
        return 0;
    }

    if (!strcmp(argv[1], "status")) {
        if (thread_running) {
            warnx("[Fantasy]running");
            return 0;

        } else {
            warnx("[Fantasy]stopped");
            return 1;
        }

        return 0;
    }
 //若果是其他,则打印不支持该类型
    usage("unrecognized command");
    return 1;
}


int read_uart_thread_main(int argc, char *argv[])
{

    int index = 0;
    char data1 = '0';
    char buffer[10] = "0";
    const char douhao[2] = ","; //逗号
    char *result = NULL;


   // const char douhao[2] = ","; //逗号
    //char *result = NULL;
   // int index = 0;
    /*
     * 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("/dev/ttyS3");//初始化串口设备
    if(false == uart_read)return -1;
    if(false == set_uart_baudrate(uart_read,115200)){     //设置波特率
        printf("[Fantasy]set_uart_baudrate is failed\n");
        return -1;
    }
    printf("[Fantasy]uart init is successful\n");

    /*进程标志变量*/
    thread_running = true;

    /*初始化数据结构体 */
    struct read_uart_sensor_s sensordata;//实例化read_uart_sensor变量,该变量是自己定义的变量
    memset(&sensordata, 0, sizeof(sensordata));//初始化sensordata变量
    /* 公告主题 */
    orb_advert_t read_uart_sensor_pub = orb_advertise(ORB_ID(read_uart_sensor), &sensordata);
    /*定义串口事件阻塞结构体及变量*/
    //px4_pollfd_struct_t fds[] = {
    //	{ .fd = serv_uart,   .events = POLLIN },
    //};
    //int error_counter = 0;

    while(!thread_should_exit){
        read(uart_read,&data1,1);
        if(data1 == 'r'){
            for(int i = 0;i <10;++i){
                read(uart_read,&data1,1);
                buffer[i] = data1;
                data1 = '0';
            }
             //逗号分割,返回下一个分割后的字符串指针,如果没有可检索的字符串,则返回一个空指针。
            result = strtok(buffer, douhao);
            while(result != NULL) {
                index++;
                switch(index){
                 case 1:
                      strncpy(sensordata.datastr,result,4);
                      break;
                 case 2:
                      strncpy(sensordata.data1str,result,4);
                      break;
                }
             result = strtok(NULL, douhao);
             }
            index = 0;
            //strncpy(sensordata.datastr,buffer,5);
            //atoi()把字符串转换成整型数
            // atof()把字符串转换成浮点数,默认为6位小数
            //sensordata.data = 0;
            //sensordata.data = sensordata.datastr;
            //sensordata.data = atoi(sensordata.datastr);
            sensordata.data = atof(sensordata.datastr);
            sensordata.data1 = atof(sensordata.data1str);
            //printf("[YCM]sonar.data=%d\n",sonardata.data);
            orb_publish(ORB_ID(read_uart_sensor), read_uart_sensor_pub, &sensordata);
        }
    }

    warnx("[YCM]exiting");
    thread_running = false;
    close(uart_read);

    fflush(stdout);
    return 0;
}

3.4.到对应机型中添加编译文件路径

我用的是雷迅X7品牌的,它的型号是雷迅X7pro。编译px4源码的指令是:

make cuav_x7pro_default

那么在这个型号基础上找到这个文件:

 之前创建的文件夹是在modules文件夹下,所以添加位置:

 read_uart_sensor

 

3.5.创建READ_UART_SENSOR.hpp

订阅read_uart_sensor消息然后将消息内容打包为MAVLINK数据帧并发送:

 

 内容如下:


#ifndef READ_UART_SENSOR_HPP
#define READ_UART_SENSOR_HPP
 
//#include <stdio.h>
#include <uORB/topics/read_uart_sensor.h>//包含uorb消息结构体的头文件
#include <v2.0/common/mavlink_msg_read_uart_sensor.h> //包含生成器生成的头文件
#include <modules/mavlink/mavlink_stream.h> //自定义类继承与MavlinkStream,所以要包含
//#include <v2.0/mavlink_types.h>
//#include <uORB/SubscriptionInterval.hpp>
//#include <uORB/uORB.h>
 
 
 
 
class MavlinkStreamReadUartSensor : public MavlinkStream
{
public:
       //explicit MavlinkStreamReadUartSensor(Mavlink *mavlink) : MavlinkStream(mavlink) {}
       static MavlinkStream *new_instance(Mavlink *mavlink)
       { return new MavlinkStreamReadUartSensor(mavlink); }
        //void update(orb_advert_t *mavlink_log_pub);
 
        static constexpr const char *get_name_static()
        {
                return "READ_UART_SENSOR";
        }
 
        static constexpr uint16_t get_id_static()
        {
                return MAVLINK_MSG_ID_READ_UART_SENSOR;
        }
        const char *get_name() const override
        {
                 return get_name_static();
                //return MavlinkStreamReadUartSensor::get_name_static();
        }
        uint16_t get_id() override
        {
                return get_id_static();
        }
 
        unsigned get_size() override
        {
                return _read_uart_sensor_sub.advertised() ? (MAVLINK_MSG_ID_READ_UART_SENSOR_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES): 0 ;
        }
 
//private:
        //uORB::Subscription _read_uart_sensor_sub{ORB_ID(read_uart_sensor)};
        //uint64_t _read_uart_sensor_time;
 
        /* do not allow top copying this class */
      //  MavlinkStreamread_uart_sensor(MavlinkStreamread_uart_sensor &) = delete;
     //   MavlinkStreamread_uart_sensor &operator = (const MavlinkStreamread_uart_sensor &) = delete;
 
private:
        explicit MavlinkStreamReadUartSensor(Mavlink *mavlink) : MavlinkStream(mavlink) {}
 
        //uORB::Subscription _read_uart_sensor_sub{ORB_ID(read_uart_sensor)};//订阅
        //_read_uart_sensor.copy(&_read_uart_sensor);//获取消息数据
 
           //~MavlinkStreamReadUartSensor();
        uORB::Subscription _read_uart_sensor_sub{ORB_ID(read_uart_sensor)};
 
 
         bool send() override //用于PX4真正发送的函数
        {
        read_uart_sensor_s orbtest;
        //read_uart_sensor_s orbtest = {};
        //struct read_uart_sensort_s;    //定义uorb消息结构体
       // mavlink_read_uart_sensor_t msg{};
        //_read_uart_sensor_sub.copy(&read_uart_sensor);
       // orb_copy(ORB_ID(read_uart_sensor), orbtest_sub_fd, &orbtest);
        //if (true)
        if(_read_uart_sensor_sub.update(&orbtest)){
 
		//int sensor_sub_fd = orb_subscribe(ORB_ID(read_uart_sensor));//订阅
		//orb_copy(ORB_ID(read_uart_sensor), sensor_sub_fd, &_read_uart_sensor);//获取消息数据
               mavlink_read_uart_sensor_t msg{};
 
                //uORB::Subscription _read_uart_sensor{ORB_ID(read_uart_sensor)};//订阅
	        //_read_uart_sensor.copy(&_read_uart_sensor);//获取消息数据
 
 
           	  //mavlink_read_uart_sensor_t msg;//定义mavlink消息结构体
           	   
 
            	msg.timestamp = orbtest.timestamp;   //这里uorb数据赋值到mavlink结构体上
            	//msg.datastr = orbtest.datastr;
            	msg.data = orbtest.data;
            	msg.data1 = orbtest.data1;
 
 
            	//
 
 
            	//msg.ll_sensor = orbtest.ll_sensor;
 
           	mavlink_msg_read_uart_sensor_send_struct(_mavlink->get_channel(), &msg);//利用生成器生成的mavlink_msg_read_uart_sensor.h头文件里面的这个函数将msg(mavlink结构体)封装成mavlink消息帧并发送;
            	printf("[Fantasy]uart init is successful\n");
                return true;
        }
        return false;
    }
};
#endif

4——功能:设置uorb自启动

如果没有写这个自启动,你需要在QGC的调试台,输入  read_uart_sensor start

版本不同,一般情况根据上下文找到这个指令的放置位置

   read_uart_sensor start

 5——功能:打印串口消息,到MAVLINK终端

5.1.创建文件夹px4_test及其文件

 5.2.添加CMakeLists.txt内容

px4_add_module(
	MODULE examples__px4_test
	MAIN px4_test
	SRCS
		px4_test.c
	DEPENDS
	)

5.3.添加 px4_test.c内容

/****************************************************************************/
/*
 * px4_test.c
 *
 * test the uart sensor app
 */
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <string.h>
#include <math.h>
 
#include <uORB/uORB.h>
#include <uORB/topics/read_uart_sensor.h>
 
__EXPORT int px4_test_main(int argc, char *argv[]);
 
int px4_test_main(int argc, char *argv[])
{
     printf("Hello Sky!\n");
 
    /* subscribe to rw_uart_sensor topic */
    int sensor_sub_fd = orb_subscribe(ORB_ID(read_uart_sensor));
    /*设置以一秒钟接收一次,并打印出数据*/
    orb_set_interval(sensor_sub_fd, 1000);
  //  bool updated;
 //   struct read_uart_sensor_data_s sensordata;
 
 
    /* one could wait for multiple topics with this technique, just using one here */
    // px4_pollfd_struct_t
        struct pollfd 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<20 ; i++) { // infinite loop
        /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
        int poll_ret = poll(fds, 1, 1000);
        /* handle the poll result */
       if (poll_ret == 0) {
            /* this means none of our providers is giving us data */
           printf("[px4_test] Got no data within a second\n");
 
       } 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) */
               printf("[px4_test] ERROR return value from poll(): %d\n", poll_ret);
           }
 
            error_counter++;
 
        } else {
        
 
            if (fds[0].revents & POLLIN) {
                /* obtained data for the first file descriptor */
                struct read_uart_sensor_s sensordata;
                /* copy sensors raw data into local buffer */
                orb_copy(ORB_ID(read_uart_sensor), sensor_sub_fd, &sensordata);
                 printf("[px4_test] sensor datastr:\t%s\t%d\n",
                       sensordata.datastr,
                       (double)sensordata.data,
                       sensordata.data1str,
                       (double)sensordata.data1);
                // printf("[px4_test] sensor data:\t%s\t%d\n",(int)sensordata.data);
            }
 
            /* there could be more file descriptors here, in the form like:
             * if (fds[1..n].revents & POLLIN) {}
             */
        }
    }
 
 //   PX4_INFO("exiting");
 
    return 0;
}

注:这个功能实在QGC上用的。在调试台输入px4_test就可以参看串口数据了。后面会演示一哈

5.4.到对应机型中添加编译文件路径

这里的“#”号功能是注释(也就是屏蔽的意思)。

px4_test

 6——编译调试

6.1.编译固件

我的是雷迅X7pro,你们的有如果不一样,编译指令就要改哈(具体的自己去搜哦)

make cuav_x7pro_default

 编译成功

6.2.下载固件

找到这个文件(后缀.px4)

 

点击确定 ,找到刚刚的.px4文件,点击打开,然后就是一个短暂的发呆时间,好了该醒一醒,地面站已经运行了。

6.3.测试显示情况

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4串口添加传感器—PX4添加自定义mavlik消息 的相关文章

  • PX4+QGC+jmavsim软件在环仿真

    一 环境修改 参考官方手册jMAVSim 仿真模拟 PX4 Developer Guide xff0c 以上环境基于上一篇内容 xff0c 未完成ROS 43 jmavsim 43 QGC环境搭建的请移步Ubuntu18 04下px4 43
  • PX4使用I2C方式添加自定义传感器(1)

    PX4使用I2C方式添加自定义传感器 xff08 1 xff09 前言 毕业设计就是要在PX4上添加一个传感器 xff08 角度传感器 xff09 xff0c 由于板子上的接口数量很少 xff0c 很是宝贵 最后只能选择通过I2C通信方式
  • Ubuntu18.04安装PX4踩坑、报错及解决方案整理

    笔者最近需要跑无人机巡检大坝的仿真 xff0c 于是在自己的Ubuntu2018 04中开始安装PX4 xff0c 问过不少之前已经装过PX4的师兄和同学 xff0c 都曾在PX4安装过程中踩过许多坑 xff0c 耗费了不少时间 xff0c
  • PX4代码学习系列博客(5)——在px4中添加自己的模块

    怎么在px4中添加自己的模块 在 px4固件目录结构和代码风格 这一节 xff0c 曾经说过NuttX是一个实时的嵌入式系统 xff0c 上面可以像windows那样运行程序 那既然是应用程序 xff0c 那我们应该也能写一些可以在Nutt
  • 从Simulink到PX4——Simulink-PX4插件安装与环境搭建

    从Simulink到PX4 Simulink PX4插件安装与环境搭建 前言0 准备工作1 安装WSL2 Setting up the PX4 Toolchain on Windows3 Setting up the PX4 Tool Ch
  • 无人机仿真—PX4编译,gazebo仿真及简单off board控制模式下无人机起飞

    无人机仿真 PX4编译 xff0c gazebo仿真及简单off board控制模式下无人机起飞 前言 在上篇记录中 xff0c 已经对整体的PX4仿真环境有了一定的了解 xff0c 现如今就要开始对无人机进行起飞等仿真环境工作 xff0c
  • PX4 -- EKF2

    文章目录 EKF2参数高度估计Range Finder滤波 单变量更新单变量更新对多变量的影响 EKF2 参数 EKF2 中有一类 GATE 参数 当测量值在 VAR GATE 范围内才会更新值 高度估计 四种高度控制方法 xff1a 气压
  • PX4模块设计之一:SITL & HITL模拟框架

    PX4模块设计之一 xff1a SITL amp HITL模拟框架 1 模拟框架1 1 SITL模拟框架1 2 HITL模拟框架 2 模拟器类型3 MAVLink API4 总结 基于PX4开源软件框架简明简介的框架设计 xff0c 逐步分
  • PX4模块设计之五:自定义MAVLink消息

    PX4模块设计之五 xff1a 自定义MAVLink消息 1 MAVLink Dialects1 1 PX4 Dialects1 2 Paprazzi Dialects1 3 MAVLink XML File Format 2 添加自定义M
  • PX4模块设计之十六:Hardfault模块

    PX4模块设计之十六 xff1a Hardfault模块 1 Hardfault模块初始化2 Hardfault模块主程序3 Hardfault命令3 1 hardfault check status3 2 hardfault rearm3
  • PX4模块设计之四十五:param模块

    PX4模块设计之四十五 xff1a param模块 1 param模块简介2 模块入口函数param main3 重要函数列表4 总结5 参考资料 1 param模块简介 Description Command to access and
  • mavros连接px4失败的usb-ttl原因

    问题描述 xff1a 最近在搞mavros xff0c 以方便协处理器和pixhawk通讯 xff0c 在按照官网教程安装mavros xff0c 设置px4 xff0c 连接硬件之后发现mavros卡在中间下不去 xff1a MAVROS
  • PX4-4-任务调度

    PX4所有的功能都封装在独立的模块中 xff0c uORB是任务间数据交互和同步的工具 xff0c 而管理和调度每个任务 xff0c PX4也提供了一套很好的机制 xff0c 这一篇我们分享PX4的任务调度机制 我们以PX4 1 11 3版
  • pixhawk px4 commander.cpp

    对于复杂的函数 xff0c 要做的就是看函数的输入是什么 来自哪里 xff0c 经过处理后得到什么 给谁用 xff0c 这样就可以把程序逻辑理清 中间的分析就是看函数如何处理的 span class hljs keyword extern
  • PX4飞控的PPM接收机

    xff08 一 xff09 原理图 xff1a PX4飞控的PPM输入捕获由协处理器完成 xff0c 接在A8引脚 xff0c 对应Timer1的通道1 xff08 二 xff09 PPM协议 xff1a PPM的每一帧数据间隔为20ms
  • PX4——Range Finder 篇

    Range Finder 此处选用的是 Benewake 下的 Lidar 参数设置 General Configuration 除了官方的参数设置外 xff0c 我在 EKF2 中还找到了 EKF2 RNG AID 参数 xff0c 用来
  • PX4之常用函数解读

    PX4Firmware 经常有人将Pixhawk PX4 APM还有ArduPilot弄混 这里首先还是简要说明一下 xff1a Pixhawk是飞控硬件平台 xff0c PX4和ArduPilot都是开源的可以烧写到Pixhawk飞控中的
  • PX4:Policy “CMP0097“ is not known to this version of CMake.

    make px4 fmu v3 时报的错 CMake版本的问题 由https blog csdn net zhizhengguan article details 118380965推测 xff0c 删除cmake policy也没事 ma
  • 四、无人机知识笔记(初级:基本运动原理)

    笔记来源于 沈阳无距科技 工业级无人机的中国名片 编程外星人 目录 一 多旋翼直升机 二 基本飞行姿态 三 多旋翼飞行原理 四 反扭力与偏航运动 五 螺旋桨 六 有刷电机和无刷电机 七 电调与PWM信号 八 动力电池 九 遥控器 十 机架设
  • 大神浅谈无人机飞控软件设计 系统性总结

    写在前面 深感自己对飞控软件 算法的知识点过于杂乱 很久没有进行系统的总结了 因此决定写几篇文章记录一些飞控开发过程的知识点 主要是针对一些软件 算法部分进行讨论 如内容有错误 欢迎指出 1 飞控软件的基本模块 无人机能够飞行主要是依靠传感

随机推荐

  • rtc使用

    首先我们要知道 xff0c rtc并非片上外设 xff0c 所以要通过连接总线以读取数据 什么是RTC RTC Real Time Clock xff1a 实时时钟 RTC是个独立的定时器 RTC模块拥有一个连续计数的计数器 xff0c 在
  • docker run命令总结

    运行 docker 容器时 xff0c 有时候我们希望它默认进入一个工作目录 xff0c 我们可以在 docker run 命令后追加参数 w 来实现 xff0c 这样我们就不需要在启动 docker 容器后再进行一次 cd 命令了 doc
  • 最新树莓派系统PUTTY用默认用户名和密码登录不上的解决方法

    最近我在树莓派配置深度学习环境 xff0c 然后直接载了别的博主的树莓派镜像 xff0c 发现博主给的用户名 xff0c 密码登不上 xff0c 于是乎 xff0c 就打算自己配置深度学习环境 xff0c 结果我下在了最新版本的树莓派镜像系
  • 关于嵌入式软件工程师的面试题(一)

    ARM是什么 xff1f ARM的分类 xff1f 1 1 是一家公司的名字 gt 专门生产IP核 xff08 内核 CPU xff09 gt 依靠专利授权盈利 1 2 是一系列ARM内核的芯片的代称 ARM7 xff0c ARM9 xff
  • 对比应用层和内核层区别

    1 应用层和内核层是计算机系统中的两个不同的层次 应用层是用户直接与计算机系统交互的层次 xff0c 它包括各种APP和libc xff08 Linux下的ANSI C的函数库 xff09 内核层是计算机系统的核心 xff0c 它提供了各种
  • uc/OS-III移植到stm32f103c8进行多任务实验

    文章目录 一 UCOSIII介绍1 简介2 UCOSIII中的任务 二 将uc OS III移植到stm32f103c81 创建CubeMx工程2 进行uCOS III的移植 三 构建三个任务1 代码添加 四 结果展示五 总结五 参考链接
  • Invalid bound statement (not found)出现原因和解决方法

    Invalid bound statement not found 出现原因和解决方法 出现的原因 xff1a mapper接口和mapper xml文件没有映射起来 解决方法 xff1a 1 mapper xml中的namespace和实
  • 服务器磁盘满了会导致ssl无法正常访问,进而导致网站样式错乱

    服务器磁盘满了会导致ssl无法正常访问 xff0c 进而导致网站样式错乱
  • 基于OpenMV和正点原子开发的自动追球小车(带云台舵机)

    电赛备赛前 xff0c 通过OpenMV加舵机云平台由 xff0c 做了一个追着球跑的小车 xff0c 由于疫情 xff0c 以前录制的视频也删除了 xff0c 最终呈现的效果和B站一位Up主的相似 xff0c 大家可以参考参考 xff0c
  • C语言For循环

    循环结构 xff1a 又称为重复结构 xff0c 在程序中处理问题需要重复处理 for循环语句 xff1a 使用灵活 可用于循环次数已确定或不确定循环次数的情况 for循环的一般结构 xff1a for xff08 表达式1 xff1b 表
  • Jetson tx2 安装jetpack_3.3手动安装cuda9.0,cudnn7.1

    1 刷机前的准备 xff08 写在前面的话 xff09 装有Ubuntu16 04或者Ubuntu18 04的电脑 xff0c 这里说的电脑可以是台式机也可以是笔记本与TX2区分开来 xff08 电脑是16 04或者18 04无所谓 xff
  • 【PX4无人机仿真】构建自己的ROS节点

    本篇文章主要是一个创建自己的ros节点的学习记录 xff0c 在学会创建简单的节点后 xff0c 参考一篇关于目标跟踪工作的博客进行了实践 xff0c 使用自己写的移动小球世界进行小球的跟踪 Demo参考 xff1a 无人机跟踪小车 文章目
  • 用U盘给nuc安装Ubuntu系统

    1 在Windows下载对应Linux的软件 xff08 一般为UNetbootin xff09 2 网上下载所需Ubuntu版本的iso文件 3 准备一个内存大于4g的U盘 4 双击运行第一步下载的软件 5 更改光盘镜像 xff0c 选择
  • keil5下载安装教程(附带兼容keil4方法)

    为了方便stm32和C51学习 xff0c 我收集资料整理了keil5的安装教程 xff0c 同时附带兼容keil4程序的方法 xff0c 避免大家在使用C51的时候再去安装keil4这个麻烦的过程 目录 一 可兼容keil4的keil5版
  • 第十三届蓝桥杯单片机设计与开发

    程序设计 客观题 感想 xff1a 这届单片机还是挺简单的 xff0c 和前几届的赛题有点像 xff0c 哦 xff0c 对 xff0c 就是第12届和第10届来着 大概2个半小时差不多全做完了 xff1b 当然客观题 xff0c 有几道不
  • PX4串口添加传感器—在QGC上添加串口数据显示

    前言 因为项目要求 xff0c xff08 在PX4上添加拉力传感器 xff0c 并把数据显示在QGC的地图上 xff09 xff0c 本人开始了苦皮的生活 从未接触飞控的我 xff0c 一来就是开发 烧脑掉发啊 但人生是无所畏惧的 在学习
  • STM32CubeMX——固件库下载以及安装

    前言 为了方便自己 xff0c 于是方便了大家 一 获取stm32Cube包 1 打开下面的链接 ST官网链接 2 下载stm32标准外设库 我要用STMCubeG413rbt6 xff0c 所以我选择STM32CubeG4系列 点击 点击
  • PX4串口添加传感器—QGC添加自定义mavlik消息

    简介 功能 xff1a 假设我想要飞控传输一个我定义的消息给地面站 xff0c 其地面站必须有一个接收处理的过程以及飞控处理发送的过程 我们传输的方式是mavlink通信方式 想要实现上面的功能 xff0c PX4和QGC就必须要有 1 修
  • 服务器扩容步骤

    第一步 xff1a 云服务器 ECS 云盘 扩容 勾选在线扩容 xff0c 提交订单 xff1b 第二步 xff1a 以此执行以下代码 xff1a 1 运行fdisk l命令查看现有云盘大小 root 64 ecshost fdisk l
  • PX4串口添加传感器—PX4添加自定义mavlik消息

    目录 1 建立 xml并生成mavlink自定义消息文件 1 1 打开终端克隆MAVLINK生成器 1 2 进入克隆目录 执行以下命令 1 3 随手建立储存文件夹 1 4 创建read uart sensor xml文件 1 5 打开MAV