开始入坑pixhawk。讲讲遇到的坑。(见解可能有误,欢迎拍砖)
1.一开始并不清楚pixhawk飞控是什么,后来发现是一个开源硬件平台,而且有两大开源飞控代码可以在其上运行。一个出自APM开源社区点击打开链接,一个出自苏黎世理工点击打开链接。
APM的代码已有多年的积累,其稳定性较好,但由于历史原因,导致其原有的硬件平台性能已经被榨干,于是APM社区人员将其移植到pixhawk的硬件平台上继续发展。也正是因为代码多年的累积,导致其结构逻辑较为晦涩,要想再做改动,非专业人士很难入门和下手。
PIXHAWK的软件是重构了APM的架构,将模块间的关系重新整理,但在算法上并非完全复制。同时又有苏黎世理工的大神加盟,代码性能和APM的相比,据说有所提高。不过最重要的是代码架构的清晰让新鲜血液更快的融入,大大降低了开发者的工作量,果断选择这个了。(dota和lol的区别吧,嘿嘿)
2.关开发环境配置。最要吐槽的是官方要求使用git clone 。而下载的速度惨目忍睹。而且无论是win还是ubuntu,clone工程以后,第一次编译你会发现非常非常慢。仔细观察会发现,他还在clone其他的依赖文件,而这个过程也是非常非常慢。。运气不好,clone失败。总之要有耐心,跟着官网的教程来。我试过从别人那儿拷贝整个工程过来,发现编译会失败,原因莫名其妙,总之还是乖乖地clone吧。
3.遇到的第一个问题,nsh启动乱码。按照官网的要求,一步步配置,到了插上usb下载固件后连接串口,发现无论如何,一打开串口就是乱码。后来发现sd卡不插时就能正常启动nsh服务。一开始没搞懂,后来查阅了\Firmware\ROMFS\px4fmu_common\init.d\rcS文件。这个是启动脚本,在最后找到了问题所在。
# Start USB shell if no microSD present, MAVLink else
if [ $LOG_FILE == /dev/null ]
then
# Try to get an USB console
nshterm /dev/ttyACM0 &
else
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
官网上的说明没有更新(好像页面上有说教程过时了,会有所不同)。在这里启动程序检测了sd卡的存在,如果存在就开启mavlink传输协议,否则开启nsh。
4.未解决的问题1。将错就错,我把代码修改了一下,去除mavlink,保留nsh,但是在插着sd卡的时候,还是无法打开nsh。实在不明白,求高人指点。
if [ $LOG_FILE == /dev/null ]
then
# Try to get an USB console
nshterm /dev/ttyACM0 &
else
nshterm /dev/ttyACM0 &
#mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
5.未解决的问题2。在跑了官网的教程代码后想试试程序自动启动。px4_daemon_app 在正常模式下运行 px4_daemon_app start 会隔10秒输出信息,px4_daemon_app stop会终止程序,px4_daemon_app status会输出当前程序是否运行。我稍稍修改了启动文件。在不插sd卡的情况下进行测试。
if [ $LOG_FILE == /dev/null ]
then
# Try to get an USB console
px4_daemon_app start
nshterm /dev/ttyACM0 &
else
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
理论上,px4_daemon_app 随着系统启动而启动,会定时输出信息,但实际上没有任何信息输出到串口上。但是奇怪的是,我直接输入px4_daemon_app status命令(注意之前没有输入px4_daemon_app start ),串口输出px4_daemon_app: running。换言之,px4_daemon_app 程序是在运行的!只是warnx("Hello daemon!\n");没有将数据输出到串口。之后输入px4_daemon_app stop 再px4_daemon_app start ,数据正常输出。
之后我在想是否是由于在启动文件中先调用了px4_daemon_app start 再调用nshterm /dev/ttyACM0 &导致的问题。于是将其位置互换,得到的结果还是一样的。没有解决。
贴一下px4_daemon_app 的代码。
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <px4_config.h>
#include <nuttx/sched.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
static bool thread_should_exit = false; /**< daemon exit flag */
static bool thread_running = false; /**< daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
/**
* daemon management function.
*/
__EXPORT int px4_daemon_app_main(int argc, char *argv[]);
/**
* Mainloop of daemon.
*/
int px4_daemon_thread_main(int argc, char *argv[]);
/**
* Print the correct usage.
*/
static void usage(const char *reason);
static void
usage(const char *reason)
{
if (reason) {
warnx("%s\n", reason);
}
warnx("usage: daemon {start|stop|status} [-p <additional params>]\n\n");
}
/**
* The daemon app only briefly exists to start
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_create().
*/
int px4_daemon_app_main(int argc, char *argv[])
{
if (argc < 2) {
usage("missing command");
return 1;
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("daemon already running\n");
/* this is not an error */
return 0;
}
thread_should_exit = false;
daemon_task = px4_task_spawn_cmd("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
px4_daemon_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
return 0;
}
if (!strcmp(argv[1], "stop")) {
thread_should_exit = true;
return 0;
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("\trunning\n");
} else {
warnx("\tnot started\n");
}
return 0;
}
usage("unrecognized command");
return 1;
}
int px4_daemon_thread_main(int argc, char *argv[])
{
warnx("[daemon] starting\n");
thread_running = true;
while (!thread_should_exit) {
warnx("Hello daemon!\n");
sleep(10);
}
warnx("[daemon] exiting.\n");
thread_running = false;
return 0;
}