PX4开发教程:如何添加QGC参数
一、概述
在PX4开发中,我们经常需要通过QGroundControl(QGC)地面站来调整飞控的各种参数。本文将详细介绍如何在PX4中添加自定义参数,并通过QGC进行调节。
二、文件结构
在PX4中添加参数主要涉及以下文件:
demo1/
├── demo.cpp # 模块源文件
├── demo.hpp # 模块头文件
├── demo_params.c # 参数定义文件
├── CMakeLists.txt # 编译配置文件
└── Kconfig # 模块配置文件
demo.cpp
/****************************************************************************
*
* Copyright (c) 2013-2019 PX4 Development Team. All rights reserved.
* 版权声明和许可证信息
*
****************************************************************************/
#include "demo.hpp"
#include <drivers/drv_hrt.h> // 高精度时间
#include <lib/perf/perf_counter.h> // 性能计数器
#include <px4_platform_common/events.h>
using namespace time_literals; // 使用时间字面量,例如 1_ms 表示1毫秒
/**
* @brief 模块构造函数
* @param vtol 是否为垂直起降飞行器(当前未使用)
*/
demo::demo(bool vtol) :
ModuleParams(nullptr), // 初始化参数系统
WorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl), // 初始化工作队列项
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) // 创建性能计数器
{
_time_stamp_last_loop = hrt_absolute_time(); // 初始化上次循环时间戳
parameters_updated(true); // 强制更新参数
}
/**
* @brief 析构函数,释放性能计数器
*/
demo::~demo()
{
perf_free(_loop_perf);
}
/**
* @brief 模块初始化函数
* @return 初始化是否成功
*/
bool demo::init()
{
// 注册位置数据的回调函数,当有新数据时会触发Run()方法
if (!_local_pos_sub.registerCallback()) {
PX4_ERR("callback registration failed");
return false;
}
return true;
}
/**
* @brief 参数更新处理函数
* @param forced 是否强制更新
*/
void demo::parameters_updated(bool forced)
{
// 检查是否需要更新参数
if (forced || _parameter_update_sub.updated()) {
// 如果有参数更新,获取并处理
if (_parameter_update_sub.updated()) {
parameter_update_s param_update;
_parameter_update_sub.copy(¶m_update);
updateParams();
}
}
}
/**
* @brief 主运行函数,由回调触发
*/
void demo::Run()
{
// 检查是否需要退出
if (should_exit()) {
_local_pos_sub.unregisterCallback(); // 取消回调注册
exit_and_cleanup(); // 清理并退出
return;
}
parameters_updated(false); // 检查参数更新
perf_begin(_loop_perf); // 开始性能计时
// 获取最新的本地位置数据
vehicle_local_position_s local_pos;
if (_local_pos_sub.update(&local_pos)) {
const hrt_abstime time_stamp_now = local_pos.timestamp_sample;
_time_stamp_last_loop = time_stamp_now;
// 根据DEMO_MODE参数值打印不同的信息
switch (_param_demo_mode.get()) {
case 1:
PX4_INFO("hello kk");
// 打印位置信息
if (local_pos.xy_valid) {
PX4_INFO("Position: x=%.2f m, y=%.2f m, z=%.2f m",
(double)local_pos.x,
(double)local_pos.y,
(double)local_pos.z);
PX4_INFO("Velocity: vx=%.2f m/s, vy=%.2f m/s, vz=%.2f m/s",
(double)local_pos.vx,
(double)local_pos.vy,
(double)local_pos.vz);
}
break;
case 2:
PX4_INFO("hello ds");
break;
default:
break;
}
}
perf_end(_loop_perf); // 结束性能计时
}
/**
* @brief 创建模块实例
* @param argc 参数数量
* @param argv 参数数组
* @return 创建结果
*/
int demo::task_spawn(int argc, char *argv[])
{
demo *instance = new demo(); // 创建新实例
if (instance) {
_object.store(instance); // 存储实例指针
_task_id = task_id_is_work_queue; // 设置任务ID
if (instance->init()) { // 初始化实例
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance; // 初始化失败,清理资源
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
/**
* @brief 处理自定义命令
*/
int demo::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
/**
* @brief 打印模块使用说明
*/
int demo::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("demo1", "template");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
/**
* @brief 模块主入口函数
* 这是一个C风格的入口点,用于启动模块
*/
extern "C" __EXPORT int demo1_main(int argc, char *argv[])
{
return demo::main(argc, argv);
}
demo.hpp
/****************************************************************************
*
* Copyright (c) 2013-2019 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.
*
****************************************************************************/
#pragma once
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_local_position.h>
#include <mathlib/math/Functions.hpp>
using namespace time_literals;
class demo : public ModuleBase<demo>, public ModuleParams, public px4::WorkItem
{
public:
demo(bool vtol = false);
~demo() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool init();
private:
void Run() override;
void parameters_updated(bool forced = true);
// 参数
DEFINE_PARAMETERS(
(ParamInt<px4::params::DEMO_MODE>) _param_demo_mode /**< demo mode parameter */
)
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)};
hrt_abstime _last_run{0};
hrt_abstime _time_stamp_last_loop{0};
perf_counter_t _loop_perf{nullptr}; /**< loop duration performance counter */
};
demo_params.c
/**
* @file demo_params.c
*
* Parameters for demo module
*/
/**
* Demo mode selection
*
* Parameter to select different demo modes:
* 1: Print 'hello kk'
* 2: Print 'hello ds'
*
* @value 1 Mode KK
* @value 2 Mode DS
* @min 1
* @max 2
* @group Demo
*/
PARAM_DEFINE_INT32(DEMO_MODE, 1);
CMakeLists
px4_add_module(
MODULE modules__demo1
MAIN demo1
SRCS
demo.cpp
demo.hpp
DEPENDS
px4_work_queue
)
Kconfig
menuconfig MODULES_DEMO1
bool "demo1"
default n
---help---
Enable support for demo1
menuconfig USER_DEMO1
bool "demo1 running as userspace module"
default n
depends on BOARD_PROTECTED && MODULES_DEMO1
---help---
Put demo1 in userspace memory
三、详细步骤
1. 参数定义(demo_params.c)
在demo_params.c文件中定义参数。这里定义了一个名为DEMO_MODE的整数参数:
/**
* Demo mode selection
*
* 参数描述:用于选择不同的演示模式
*
* @value 1 Mode KK // 模式1说明
* @value 2 Mode DS // 模式2说明
* @min 1 // 最小值
* @max 2 // 最大值
* @group Demo // 参数组
*/
PARAM_DEFINE_INT32(DEMO_MODE, 1); // 默认值为1
2. 参数声明(demo.hpp)
在模块的头文件中声明参数:
class demo : public ModuleBase<demo>, public ModuleParams, public px4::WorkItem
{
private:
// 参数声明
DEFINE_PARAMETERS(
(ParamInt<px4::params::DEMO_MODE>) _param_demo_mode /**< demo mode parameter */
)
// 其他成员...
};
3. 参数使用(demo.cpp)
在源文件中使用参数:
// 构造函数中初始化参数系统
demo::demo(bool vtol) :
ModuleParams(nullptr), // 初始化参数系统
WorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl)
{
parameters_updated(true); // 强制更新参数
}
// 参数更新处理函数
void demo::parameters_updated(bool forced)
{
if (forced || _parameter_update_sub.updated()) {
parameter_update_s param_update;
_parameter_update_sub.copy(¶m_update);
updateParams();
}
}
// 在主循环中使用参数
void demo::Run()
{
parameters_updated(false); // 检查参数更新
// 获取最新的本地位置数据
vehicle_local_position_s local_pos;
if (_local_pos_sub.update(&local_pos)) {
// 根据参数值执行不同操作
switch (_param_demo_mode.get()) {
case 1:
PX4_INFO("hello kk");
// 打印位置信息
if (local_pos.xy_valid) {
PX4_INFO("Position: x=%.2f m, y=%.2f m, z=%.2f m",
(double)local_pos.x,
(double)local_pos.y,
(double)local_pos.z);
}
break;
case 2:
PX4_INFO("hello ds");
break;
}
}
}
四、参数属性说明
1. 常用参数类型
PARAM_DEFINE_INT32:32位整数PARAM_DEFINE_FLOAT:浮点数PARAM_DEFINE_BOOL:布尔值
2. 参数属性标签
@min:最小值@max:最大值@value:枚举值说明@decimal:小数位数@increment:调节步长@group:参数组@reboot_required:是否需要重启@unit:单位
五、参数操作方法
1. 通过QGC操作
- 编译并运行PX4
- 打开QGC地面站
- 进入参数设置页面
- 在对应的参数组中找到并修改参数
2. 通过命令行操作
# 查看参数值
param show DEMO_MODE
# 设置参数值
param set DEMO_MODE 1
# 保存参数
param save
六、注意事项
- 参数命名建议使用大写字母,用下划线分隔单词
- 添加新参数后需要重新编译PX4固件
- 参数会保存在非易失性存储器中,重启后保持设置值
- 建议使用模块名作为参数前缀,避免命名冲突
- 参数描述要清晰,便于其他开发者理解
七、调试技巧
- 使用
PX4_INFO打印参数值进行调试 - 可以通过
parameters_updated函数监控参数变化 - 注意检查参数有效性,避免使用无效值
八、参考资料
- PX4开发者指南
- PX4源码
- QGroundControl用户手册
本文介绍了在PX4中添加和使用QGC参数的完整流程,希望对大家有所帮助。如有问题,欢迎在评论区讨论。
标签:PX4开发 无人机 QGroundControl 嵌入式开发
2905

被折叠的 条评论
为什么被折叠?



