本篇文章主要记录自己在开发PX4固件时解决问题的一些经历,主要用于自己往日回顾与学习参考。如有疏漏请大家见谅,也可以交流讨论!
0、主要实现目的:
- 1.自定义uORB消息,并运行在工作队列中(主要用AS5047P获取电机绝对角度)
- 2.自定义Mavlink消息,映射1中自定义的uORB消息
- 3.修改QGC相应源码,并使用QT编译生成新的自定义QGC界面,显示Mavlink消息
本文章主要参考了其他相关文章,主要为整理归纳,目的是方便自己往日参考,下面给出参考资料:
这两篇我认为是讲的比较全面的文章。
一、自定义uORB消息,并并创建相应的函数执行消息的发布
关于uORB的了解,可以参考这篇文章:
首先,在这个路径下创建需要的自定义uORB message:PX4-Autopilot/msg/SensorAs5047p.m
uint64 timestamp # time since system start (microseconds) uint8 sinpwm_index_x # the sinpwm_index of the x axial(pitching motion) uint8 sinpwm_index_y # the sinpwm_index of the y axial(rolling motion) float64 ave_n #the average angular velocity of motor(for calculate the work item interval time) float64 abs_angle #the absolute angle of motor(for calculate the sinpwm)
然后,在msg/CMakeLists.txt “set(msg_files”中添加自己定义的msg:
WheelEncoders.msg
Wind.msg
YawEstimatorStatus.msg
SensorAs5047p.msg
)
创建完自定义的uORB后,接下来要做的就是编写处理所需要的数据并将他们发布的函数(即uORB 的消息发布和订阅):
这里我在src/modules/as5047p路径下创建了我自定义的角度获取和uORB处理发布函数,需要创建四个文件:
CMakeLists.txt:
px4_add_module() 方法根据模块描述生成静态库。
- MODULE块是模块的唯一固件名称(按照惯例,模块名称的前缀是src之后的父路径)
- MAIN块列出了模块的入口点,它将命令注册到 NuttX,以便可以从 PX4 shell 或 SITL 控制台调用它。
Kconfig:
Kconfig文件里面定义了:
- 任务的名称: as5047p
- Kconfig符号:MODULES_AS5047P
- 默认选择:n
- 该任务的描述
cpp、hpp文件即函数实现:
class AS5047P : public ModuleBase<AS5047P>, public ModuleParams, public px4::ScheduledWorkItem,public device::SPI
这里我采用工作队列的实现方法,继承了ModuleBase、ModuleParams、px4::ScheduledWorkItem、device::SPI几个类来实现。
// Publications uORB::Publication<sensor_as5047p_s> _sensor_as5047p_pub{ORB_ID(sensor_as5047p)}; void AS5047P::publish_params(double angle,double n) { sensor_as5047p_s data{}; data.abs_angle=angle; data.ave_n=n;//update ave_w data.timestamp = hrt_absolute_time(); _sensor_as5047p_pub.publish(data);//publish the updated data }
这是uORB发布的核心代码。
定义完该module后:在make的时候make holybro_durandal-v1_default boardconfig勾选自己定义的module。这样才能在Mavlink 控制台中运行。(或者可以直接通过在PX4-Autopilot/ROMFS/px4fmu_common/init.d/rcS文件中直接添加一行“as5047p start”这样该文件就会在设备气动时自动启动)
通过以上的步骤就可以将我们采集到的数据发布到uORB中了。接下来就是如何使用该uORB消息。
二、自定义Mavlink消息,并将我们的自定义uORB消息与其映射
找到PX4源码中定义Mavlink消息的文件:src/modules/mavlink/mavlink/message_definitions/v1.0/common.xml。在其中自定义一条“AS5047P”消息:
<message id="666" name="AS5047P">
<description> Show the parameters of sensor AS5047P(abs angle and angular velocity).</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (synced to UNIX time or since system boot).</field>
<field type="double" name="abs_angle">abs_angle.</field>
<field type="double" name="ave_n">ave_n.</field>
</message>
其中id不能与其他重复,make后可以在build/holybro_durandal-v1_default/mavlink/common/mavlink_msg_as5047p.h中查看:
#pragma once
// MESSAGE AS5047P PACKING
#define MAVLINK_MSG_ID_AS5047P 666
typedef struct __mavlink_as5047p_t {
uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/
double abs_angle; /*< abs_angle.*/
double ave_n; /*< ave_n.*/
} mavlink_as5047p_t;
#define MAVLINK_MSG_ID_AS5047P_LEN 24
#define MAVLINK_MSG_ID_AS5047P_MIN_LEN 24
#define MAVLINK_MSG_ID_666_LEN 24
#define MAVLINK_MSG_ID_666_MIN_LEN 24
#define MAVLINK_MSG_ID_AS5047P_CRC 147
#define MAVLINK_MSG_ID_666_CRC 147
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AS5047P { \
666, \
"AS5047P", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_as5047p_t, time_usec) }, \
{ "abs_angle", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_as5047p_t, abs_angle) }, \
{ "ave_n", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_as5047p_t, ave_n) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AS5047P { \
"AS5047P", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_as5047p_t, time_usec) }, \
{ "abs_angle", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_as5047p_t, abs_angle) }, \
{ "ave_n", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_as5047p_t, ave_n) }, \
} \
}
#endif
/**
* @brief Pack a as5047p message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
* @param abs_angle abs_angle.
* @param ave_n ave_n.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_as5047p_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, double abs_angle, double ave_n)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AS5047P_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_double(buf, 8, abs_angle);
_mav_put_double(buf, 16, ave_n);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AS5047P_LEN);
#else
mavlink_as5047p_t packet;
packet.time_usec = time_usec;
packet.abs_angle = abs_angle;
packet.ave_n = ave_n;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AS5047P_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AS5047P;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
}
/**
* @brief Pack a as5047p message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
* @param abs_angle abs_angle.
* @param ave_n ave_n.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_as5047p_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,double abs_angle,double ave_n)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AS5047P_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_double(buf, 8, abs_angle);
_mav_put_double(buf, 16, ave_n);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AS5047P_LEN);
#else
mavlink_as5047p_t packet;
packet.time_usec = time_usec;
packet.abs_angle = abs_angle;
packet.ave_n = ave_n;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AS5047P_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AS5047P;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
}
/**
* @brief Encode a as5047p struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param as5047p C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_as5047p_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_as5047p_t* as5047p)
{
return mavlink_msg_as5047p_pack(system_id, component_id, msg, as5047p->time_usec, as5047p->abs_angle, as5047p->ave_n);
}
/**
* @brief Encode a as5047p struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param as5047p C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_as5047p_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_as5047p_t* as5047p)
{
return mavlink_msg_as5047p_pack_chan(system_id, component_id, chan, msg, as5047p->time_usec, as5047p->abs_angle, as5047p->ave_n);
}
/**
* @brief Send a as5047p message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
* @param abs_angle abs_angle.
* @param ave_n ave_n.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_as5047p_send(mavlink_channel_t chan, uint64_t time_usec, double abs_angle, double ave_n)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AS5047P_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_double(buf, 8, abs_angle);
_mav_put_double(buf, 16, ave_n);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AS5047P, buf, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
#else
mavlink_as5047p_t packet;
packet.time_usec = time_usec;
packet.abs_angle = abs_angle;
packet.ave_n = ave_n;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AS5047P, (const char *)&packet, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
#endif
}
/**
* @brief Send a as5047p message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_as5047p_send_struct(mavlink_channel_t chan, const mavlink_as5047p_t* as5047p)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_as5047p_send(chan, as5047p->time_usec, as5047p->abs_angle, as5047p->ave_n);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AS5047P, (const char *)as5047p, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
#endif
}
#if MAVLINK_MSG_ID_AS5047P_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_as5047p_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, double abs_angle, double ave_n)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_double(buf, 8, abs_angle);
_mav_put_double(buf, 16, ave_n);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AS5047P, buf, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
#else
mavlink_as5047p_t *packet = (mavlink_as5047p_t *)msgbuf;
packet->time_usec = time_usec;
packet->abs_angle = abs_angle;
packet->ave_n = ave_n;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AS5047P, (const char *)packet, MAVLINK_MSG_ID_AS5047P_MIN_LEN, MAVLINK_MSG_ID_AS5047P_LEN, MAVLINK_MSG_ID_AS5047P_CRC);
#endif
}
#endif
#endif
// MESSAGE AS5047P UNPACKING
/**
* @brief Get field time_usec from as5047p message
*
* @return [us] Timestamp (synced to UNIX time or since system boot).
*/
static inline uint64_t mavlink_msg_as5047p_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field abs_angle from as5047p message
*
* @return abs_angle.
*/
static inline double mavlink_msg_as5047p_get_abs_angle(const mavlink_message_t* msg)
{
return _MAV_RETURN_double(msg, 8);
}
/**
* @brief Get field ave_n from as5047p message
*
* @return ave_n.
*/
static inline double mavlink_msg_as5047p_get_ave_n(const mavlink_message_t* msg)
{
return _MAV_RETURN_double(msg, 16);
}
/**
* @brief Decode a as5047p message into a struct
*
* @param msg The message to decode
* @param as5047p C-struct to decode the message contents into
*/
static inline void mavlink_msg_as5047p_decode(const mavlink_message_t* msg, mavlink_as5047p_t* as5047p)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
as5047p->time_usec = mavlink_msg_as5047p_get_time_usec(msg);
as5047p->abs_angle = mavlink_msg_as5047p_get_abs_angle(msg);
as5047p->ave_n = mavlink_msg_as5047p_get_ave_n(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AS5047P_LEN? msg->len : MAVLINK_MSG_ID_AS5047P_LEN;
memset(as5047p, 0, MAVLINK_MSG_ID_AS5047P_LEN);
memcpy(as5047p, _MAV_PAYLOAD(msg), len);
#endif
}
接下来在./src/modules/mavlink/streams/创建一个hpp文件,内容仿照其他文件就行,将其改写一下,主要作用就是将UORB消息中的内容复制到Mavlink结构体中:
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef AS5047P_HPP
#define AS5047P_HPP
#include <uORB/topics/sensor_as5047p.h>
class MavlinkStreamAS5047P : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamAS5047P(mavlink); }
static constexpr const char *get_name_static() { return "AS5047P"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_AS5047P; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
return _sensor_as5047p_sub.advertised() ? MAVLINK_MSG_ID_AS5047P_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
}
private:
explicit MavlinkStreamAS5047P(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::Subscription _sensor_as5047p_sub{ORB_ID(sensor_as5047p)};
bool send() override
{
sensor_as5047p_s as5047p;
// send a MAVLink message whether or not the data changed
if (_sensor_as5047p_sub.copy(&as5047p)) {
mavlink_as5047p_t msg{};
msg.time_usec = as5047p.timestamp;
msg.abs_angle = as5047p.abs_angle;
msg.ave_n = as5047p.ave_n;
mavlink_msg_as5047p_send_struct(_mavlink->get_channel(), &msg);
return true;
}
return false;
}
};
#endif // AS5047P_HPP
其中的:
uORB::Subscription _sensor_as5047p_sub{ORB_ID(sensor_as5047p)};
sensor_as5047p_s as5047p;
// send a MAVLink message whether or not the data changed
if (_sensor_as5047p_sub.copy(&as5047p)) {
即订阅我们刚刚发布的uORB消息。
接着找到./src/modules/mavlink/mavlink_messages.cpp文件,对其进行两处修改:
#include "streams/AS5047P.hpp"//包含头文件
#if defined(AS5047P_HPP)
create_stream_list_item<MavlinkStreamAS5047P>(),
#endif // AS5047P_HPP
最后找到./src/modules/mavlink/mavlink_main.cpp文件,在“switch (_mode)”语句的上方增加一行,配置mavlink消息的发送速率:(我这里是100Hz)
configure_stream_local("AS5047P",100.0f);
至此,PX4部分的源码修改已经全部完成,只需将编译好的源码烧入飞控即可。
三、修改QGC源码,在地面站界面中显示自定义Mavlink消息
这部分内容主要参考这篇文章:
其中包括几个部分,我本人也不是专业的就不展开将了,主要讲一下我在这个过程中遇到的一些问题和经验分析:
Windows下的QT编译环境搭建:
注意:
1.QT版本与后续需要编译的QGC源码版本要匹配。(我的QGC版本为v4.3.0,对应的QT版本为5.15.18)
2.一定要添加环境变量
3.构建时后的一些tips参考:QGC使用Qt构建,一些注意事项-优快云博客
4.我在QGC debug编译的时候没报错,release编译的时候报错了300多行(参考了:windos10安装QGC4.2编译环境_qgc windows 环境-优快云博客),该部分内容还没解决,现在只能debug。
QGC源码下载:
最好(建议只使用git下载,包括缺失的模块git)使用Git下载:参考WIN10源码编译安装QGC-V3.4_qgc编译-优快云博客
或者找其他人下载好的:QGC4.4稳定版二次开发环境搭建windows_qgc开发环境搭建-优快云博客
(给了链接)
不适用Git下载会出现很多文件没有下载的错误,处理起来很麻烦(不要问我为什么知道的,一言难尽0.0)
但有些文件还是会缺失,具体操作参考:Ubuntu20.04安装QGroundcontrol开发环境_ubuntu20.04打开qgc-优快云博客
对于该问题:
下载文件后在QGCExternalLibs.pri中添加:
INCLUDEPATH += libs/libevents/libevents/libs/cpp/parse/nlohmann_json/include INCLUDEPATH += libs/airmapd/include
其余步骤参考:PX4自定义UORB和Mavlink消息,并发送到QGC_mavlink inspector-优快云博客进行没什么大问题,最后在QT中编译构建修改后的QGC源码就行。
(我在编译过程中遇到了这种错误,将对于没有调用的代码注释后解决了,其他问题可以参考其他文章中给出的解决方案)
最终,打开编译后的QGC地面站,连接飞控,可以在“Analyze Tools - Mavlink Inspector”中查看Mavlink列表:
因为我是吧我的文件直接写入启动文件了(文件自动执行),如果没有进行(或者可以直接通过在PX4-Autopilot/ROMFS/px4fmu_common/init.d/rcS文件中直接添加一行“as5047p start”这样该文件就会在设备气动时自动启动)这部操作的话需要先通过Mavlink Console启动线程,就可以看到消息了。
以上是本篇文章所有内容,欢迎大家找我交流!