文章目录
- 前言
- 一、概述
- 二、二次开发基础(自定义工作队列,自定义uorb)
- 三、自定义串口驱动(添加一个毫米波雷达并定高)
- 四、自定义I2C驱动(驱动一个oled显示屏)
- 五、自定义参数
- 六、自定义日志
- 七、自定义机型
- 八、自定义mavlink消息和QGC通信
- 九、自定义mavlink消息和MAVROS通信
- 十、OFFBAORD控制接口(状态控制 pwm输出)
- 十一、基于模型开发(替换控制律/基于模型的编队)
前言
交流学习可加文章底部作者微信
本教程的适用对象:
1、零基础或者有较少基础(尚未入门)
2、希望在短时间里(一到两个月)学会对PX4进行二次开发的开源爱好者或工程师
硬件:
pixhawk飞控
超维M系列无人机
软件:
PX4 1.13.3
QGC4.2.4
课程源码:https://gitee.com/Mbot_admin/px4-1.13.3-cwkj
一、概述
二、二次开发基础(自定义工作队列,自定义uorb)
在modules文件夹下添加work_item文件夹
添加下面四个文件
CMakeLists.txt
px4_add_module(MODULE modules__work_itemMAIN work_item_testCOMPILE_FLAGS#-DDEBUG_BUILD # uncomment for PX4_DEBUG output#-O0 # uncomment when debuggingSRCSWorkItemTest.cppWorkItemTest.hppDEPENDSpx4_work_queue)
Kconfig
menuconfig MODULES_WORK_ITEMbool "work_item"default n---help---Enable support for work_item
WorkItemTest.cpp
#include "WorkItemTest.hpp"WorkItemTest::WorkItemTest() :ModuleParams(nullptr),ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1)
{
}WorkItemTest::~WorkItemTest()
{perf_free(_loop_perf);perf_free(_loop_interval_perf);
}bool WorkItemTest::init()
{
ScheduleOnInterval(100000_us);return true;
}void WorkItemTest::Run()
{if (should_exit()) {ScheduleClear();exit_and_cleanup();return;}perf_begin(_loop_perf);perf_count(_loop_interval_perf);// Check if parameters have changedif (_parameter_update_sub.updated()) {// clear updateparameter_update_s param_update;_parameter_update_sub.copy(¶m_update);updateParams(); // update module parameters (in DEFINE_PARAMETERS)}PX4_INFO("test workitem");perf_end(_loop_perf);
}int WorkItemTest::task_spawn(int argc, char *argv[])
{WorkItemTest *instance = new WorkItemTest();if (instance) {_object.store(instance);_task_id = task_id_is_work_queue;if (instance->init()) {return PX4_OK;}} else {PX4_ERR("alloc failed");}delete instance;_object.store(nullptr);_task_id = -1;return PX4_ERROR;
}int WorkItemTest::print_status()
{perf_print_counter(_loop_perf);perf_print_counter(_loop_interval_perf);return 0;
}int WorkItemTest::custom_command(int argc, char *argv[])
{return print_usage("unknown command");
}int WorkItemTest::print_usage(const char *reason)
{if (reason) {PX4_WARN("%s\n", reason);}PRINT_MODULE_DESCRIPTION(R"DESCR_STR(
### Description
Example of a simple module running out of a work queue.)DESCR_STR");PRINT_MODULE_USAGE_NAME("work_item_example", "template");PRINT_MODULE_USAGE_COMMAND("start");PRINT_MODULE_USAGE_DEFAULT_COMMANDS();return 0;
}extern "C" __EXPORT int work_item_test_main(int argc, char *argv[])
{return WorkItemTest::main(argc, argv);
}
WorkItemTest.hpp
#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 <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/orb_test.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/vehicle_status.h>using namespace time_literals;class WorkItemTest : public ModuleBase<WorkItemTest>, public ModuleParams, public px4::ScheduledWorkItem
{
public:WorkItemTest();~WorkItemTest() 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();int print_status() override;private:void Run() override;// PublicationsuORB::Publication<orb_test_s> _orb_test_pub{ORB_ID(orb_test)};// SubscriptionsuORB::SubscriptionCallbackWorkItem _sensor_accel_sub{this, ORB_ID(sensor_accel)}; // subscription that schedules WorkItemExample when updateduORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; // subscription limited to 1 Hz updatesuORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; // regular subscription for additional data// Performance (perf) countersperf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": interval")};// ParametersDEFINE_PARAMETERS((ParamInt<px4::params::SYS_AUTOSTART>) _param_sys_autostart, /**< example parameter */(ParamInt<px4::params::SYS_AUTOCONFIG>) _param_sys_autoconfig /**< another parameter */)bool _armed{false};
};
修改仿真的编译脚本
添加如下:
CONFIG_MODULES_WORK_ITEM=y
然后执行
make px4_sitl_default gazbo
启动仿真后执行:
work_item_test start
正常的话会打印下面的信息
三、自定义串口驱动(添加一个毫米波雷达并定高)
PX4二次开发快速入门(三):自定义串口驱动
四、自定义I2C驱动(驱动一个oled显示屏)
五、自定义参数
在第一节的基础上进一步修改
添加params.c
params.c内容如下:
PARAM_DEFINE_FLOAT(PARAM_TEST1, 0.2f);
PARAM_DEFINE_INT32(PARAM_TEST2, 0);
CMakeLists.txt
px4_add_module(MODULE modules__work_itemMAIN work_item_testCOMPILE_FLAGS#-DDEBUG_BUILD # uncomment for PX4_DEBUG output#-O0 # uncomment when debuggingSRCSWorkItemTest.cppWorkItemTest.hppDEPENDSpx4_work_queue)
Kconfig
menuconfig MODULES_WORK_ITEMbool "work_item"default n---help---Enable support for work_item
WorkItemTest.cpp
#include "WorkItemTest.hpp"WorkItemTest::WorkItemTest() :ModuleParams(nullptr),ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1)
{
}WorkItemTest::~WorkItemTest()
{perf_free(_loop_perf);perf_free(_loop_interval_perf);
}bool WorkItemTest::init()
{
ScheduleOnInterval(100000_us);return true;
}void WorkItemTest::Run()
{if (should_exit()) {ScheduleClear();exit_and_cleanup();return;}perf_begin(_loop_perf);perf_count(_loop_interval_perf);// Check if parameters have changedif (_parameter_update_sub.updated()) {// clear updateparameter_update_s param_update;_parameter_update_sub.copy(¶m_update);updateParams(); // update module parameters (in DEFINE_PARAMETERS)}double param_test1=_param_test1.get();int param_test2=_param_test2.get();PX4_INFO("param_test1=%lf param_test2=%d\n",param_test1,param_test2);PX4_INFO("test workitem");perf_end(_loop_perf);
}int WorkItemTest::task_spawn(int argc, char *argv[])
{WorkItemTest *instance = new WorkItemTest();if (instance) {_object.store(instance);_task_id = task_id_is_work_queue;if (instance->init()) {return PX4_OK;}} else {PX4_ERR("alloc failed");}delete instance;_object.store(nullptr);_task_id = -1;return PX4_ERROR;
}int WorkItemTest::print_status()
{perf_print_counter(_loop_perf);perf_print_counter(_loop_interval_perf);return 0;
}int WorkItemTest::custom_command(int argc, char *argv[])
{return print_usage("unknown command");
}int WorkItemTest::print_usage(const char *reason)
{if (reason) {PX4_WARN("%s\n", reason);}PRINT_MODULE_DESCRIPTION(R"DESCR_STR(
### Description
Example of a simple module running out of a work queue.)DESCR_STR");PRINT_MODULE_USAGE_NAME("work_item_example", "template");PRINT_MODULE_USAGE_COMMAND("start");PRINT_MODULE_USAGE_DEFAULT_COMMANDS();return 0;
}extern "C" __EXPORT int work_item_test_main(int argc, char *argv[])
{return WorkItemTest::main(argc, argv);
}
WorkItemTest.hpp
#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 <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/orb_test.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/vehicle_status.h>using namespace time_literals;class WorkItemTest : public ModuleBase<WorkItemTest>, public ModuleParams, public px4::ScheduledWorkItem
{
public:WorkItemTest();~WorkItemTest() 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();int print_status() override;private:void Run() override;// PublicationsuORB::Publication<orb_test_s> _orb_test_pub{ORB_ID(orb_test)};// SubscriptionsuORB::SubscriptionCallbackWorkItem _sensor_accel_sub{this, ORB_ID(sensor_accel)}; // subscription that schedules WorkItemExample when updateduORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; // subscription limited to 1 Hz updatesuORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; // regular subscription for additional data// Performance (perf) countersperf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": interval")};// ParametersDEFINE_PARAMETERS((ParamInt<px4::params::SYS_AUTOSTART>) _param_sys_autostart, /**< example parameter */(ParamInt<px4::params::SYS_AUTOCONFIG>) _param_sys_autoconfig, /**< another parameter */(ParamFloat<px4::params::PARAM_TEST1>) _param_test1, /**< example parameter */(ParamInt<px4::params::PARAM_TEST2>) _param_test2 /**< another parameter */)bool _armed{false};
};
修改仿真的编译脚本
添加如下:
CONFIG_MODULES_WORK_ITEM=y
然后先执行(不执行这一步后面会报错)
make distclean
再执行
make parameters_metadata
最后执行
make px4_sitl_default gazbo
启动仿真后执行(注意要启动work_item_test ,不然地面站搜不到参数):
work_item_test start
如果在启动work_item_test 之前已经打开了地面站,还需要再刷新一下参数
就可以搜到添加的参数