PX4飞控-自定义发送MavLink消息


PX4飞控-自定义发送MavLink消息

一、自定义XML文件

1

如图所示。

这相当于定义了一个结构体,结构体里面就有一个类型为uint8_t的u8元素。

使用的id端口为150,这里注意不要与已经存在的id重复。

二、使用XML文件生成对应的头文件

在这里需要使用到一个工具mavlink_generator,它的安装方法比较简单。

在命令行依次输入下方命令即可完成安装:

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

cd mavlink
    
git submodule update --init --recursive
    
python -m mavgenerate

之后会弹出下图界面:

2

点击第一个Browse,选择之前新建的XML文件。

点击第二个Browse,选择最终的输出文件夹。

将Language切换为C,其他保持默认。

最终选择界面如下图所示

3

点击Generate按钮,会弹出一个窗口,点击OK即可。

4

最后成功生成最终文件。

三、将生成的头文件添加到源代码中

在生成目录找到mavlink_msg_mytestmessage.h(这个文件名不是固定的,根据个人定义而不同。)

将这个文件复制到源代码/mavlink/include/mavlink/v2.0/common目录下。

同时在同目录的common.h文件中添加刚才复制的头文件。

5

class MavlinkMytestMessage : public MavlinkStream
{
public:
	const char *get_name() const override
	{
		return MavlinkMytestMessage::get_name_static();
	}

	static constexpr const char *get_name_static()
	{
		return "MytestMessage";
	}

	static constexpr uint16_t get_id_static()
	{
		return MAVLINK_MSG_ID_TEST_TYPES;
	}

	uint16_t get_id() override
	{
		return get_id_static();
	}

	bool const_rate() override
	{
		return true;
	}

	static MavlinkStream *new_instance(Mavlink *mavlink)
	{
		return new MavlinkMytestMessage(mavlink);
	}

	unsigned get_size() override
	{
		return MAVLINK_MSG_ID_TEST_TYPES_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
	}

private:
	/* do not allow top copying this class */
	MavlinkMytestMessage(MavlinkMytestMessage &) ;
	MavlinkMytestMessage &operator = (const MavlinkMytestMessage &) ;

protected:
	explicit MavlinkMytestMessage(Mavlink *mavlink) : MavlinkStream(mavlink)
	{}
	~MavlinkMytestMessage()
	{}
    /* 发送函数 */
	bool send(const hrt_abstime t) override
	{
        /* 创建结构体 */
		mavlink_test_types_t test;
        /* 结构体变量赋值 */
		test.u8 = 150;
        /* 发送函数 */
		mavlink_msg_test_types_send_struct(_mavlink->get_channel(), &test);
		return true;
	}
};

mavlink_messages.cpp文件中添加如上面代码差不多的类。有一些地方需要对应起来,也可以参考这个文件中其他类的定义来进行修改和理解。

添加完自定义的类之后还需要修改static const StreamListItem streams_list这个列表。

这个列表里面存放着目前所有需要输出的Mavlink消息,可以根据自己的需要进行取舍,注释掉不需要的消息。

要发送自定义的消息,就需要把刚才自定义的类添加到这个列表中来。

6

需要在Mavlink::configure_streams_to_default(const char *configure_single_stream)这个函数里面添加要发送的消息。(位置差不多在函数尾处)

7

这个函数第二个参数是发送速率,可以通过修改它来更改发送速率。

六、 上传固件

编译已经修改过的源代码,并上传到飞行器中。之后查看Mavlink消息就会找到自己定义的消息了。

推荐测试的时候把其他所有消息全部注释,只留自己自定义的消息,这样可以更清晰的看到输出结果。

QGC地面站可能无法正常查看到自己自定义的消息,可能还需要进一步修改地面站的配置。所以这里还是推荐使用串口助手直接调试查看。


文章作者: LightningMaster
版权声明: 本博客所有文章除特別声明外,均采用 CC BY 4.0 许可协议。转载请注明来源 LightningMaster !
评论
  目录