Pixhawk---通過串列埠方式新增一個自定義感測器(超聲波為例)
阿新 • • 發佈:2019-01-06
Pixhawk—新增一個自定義感測器—超聲波(串列埠方式)
1 說明
首先超聲波模組是通過串列埠方式傳送(Tx)出資料,使用的模組資料傳送週期為100ms,資料格式為:
R0034 R0122 R0122 R0046 R0127 R0044 R0044 R0125 R0034 R0037 R0041 R0122 R0122 .....
則可以通過Pixhawk板上的串列埠來接收(Rx)資料,即將超聲波的Tx介面連線到Pixhawk板上的Rx介面。
Pixhawk板上串列埠說明:
測試使用Pixhawk板上TELEM2介面的USART2,對應的Nuttx UART裝置檔案尾/dev/ttyS2
:
2 讀取資料測試
步驟:
- 在
Firmware/src/modules
中新增一個新的資料夾,命名為rw_uart
- 在
rw_uart
資料夾中建立module.mk
檔案,並輸入以下內容:
- MODULE_COMMAND = rw_uart
- SRCS = rw_uart.c
- 在
rw_uart
資料夾中建立rw_uart.c
檔案 - 註冊新新增的應用到NuttShell中。
Firmware/makefiles/nuttx/config_px4fmu-v2_default.mk
檔案中新增如下內容:
- MODULES += modules/rw_uart
rw_uart.c
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
__EXPORT int rw_uart_main(int argc, char *argv[]);
static int uart_init(char * uart_name);
static int set_uart_baudrate(const int fd, unsigned int baud);
int set_uart_baudrate(const int fd, unsigned int baud)
{
int speed;
switch (baud) {
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
default:
warnx("ERR: baudrate: %d\n", baud);
return -EINVAL;
}
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
tcgetattr(fd, &uart_config);
/* clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* no parity, one stop bit */
uart_config.c_cflag &= ~(CSTOPB | PARENB);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetispeed)\n", termios_state);
return false;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetospeed)\n", termios_state);
return false;
}
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERR: %d (tcsetattr)\n", termios_state);
return false;
}
return true;
}
int uart_init(char * uart_name)
{
int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);
if (serial_fd < 0) {
err(1, "failed to open port: %s", uart_name);
return false;
}
return serial_fd;
}
int rw_uart_main(int argc, char *argv[])
{
char data = '0';
char buffer[4] = "";
/*
* TELEM1 : /dev/ttyS1
* TELEM2 : /dev/ttyS2
* GPS : /dev/ttyS3
* NSH : /dev/ttyS5
* SERIAL4: /dev/ttyS6
* N/A : /dev/ttyS4
* IO DEBUG (RX only):/dev/ttyS0
*/
int uart_read = uart_init("/dev/ttyS2");
if(false == uart_read)return -1;
if(false == set_uart_baudrate(uart_read,9600)){
printf("[YCM]set_uart_baudrate is failed\n");
return -1;
}
printf("[YCM]uart init is successful\n");
while(true){
read(uart_read,&data,1);
if(data == 'R'){
for(int i = 0;i <4;++i){
read(uart_read,&data,1);
buffer[i] = data;
data = '0';
}
printf("%s\n",buffer);
}
}
return 0;
}
編譯並刷韌體
- make clean
- make upload px4fmu-v2_default
檢視app
- 在NSH終端中輸入
help
,在Builtin Apps中出現rw_uart
應用。
- 在NSH終端中輸入
- 執行rw_uart應用(前提是模組與Pixhawk連線好)
- 在NSH終端中輸入
rw_uart
,回車,檢視超聲波的列印資料。
- 在NSH終端中輸入
3 釋出超聲波的資料
在無人機執行時,首先是要將應用隨系統啟動時就啟動起來的,且將獲得的超聲波資料不斷的釋出出去,從而讓其他應用得以訂閱使用。這裡也使用Pixhawk裡面的通用模式,即主執行緒,檢測app命令輸入,建立一個執行緒來不斷的釋出資料。
3.1 定義主題和釋出主題
- 在
modules/rw_uart
資料夾下建立一個檔案:rw_uart_sonar_topic.h
rw_uart_sonar_topic.h
#ifndef __RW_UART_SONAR_H_
#define __RW_UART_SONAR_H_
#include <stdint.h>
#include <uORB/uORB.h>
/*宣告主題,主題名自定義*/
ORB_DECLARE(rw_uart_sonar);
/* 定義要釋出的資料結構體 */
struct rw_uart_sonar_data_s{
char datastr[5]; //原始資料
int data; //解析資料,單位:mm
};
#endif
rw_uart.c
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include "rw_uart_sonar_topic.h"
/* 定義主題 */
ORB_DEFINE(rw_uart_sonar, struct rw_uart_sonar_data_s);
static bool thread_should_exit = false;
static bool thread_running = false;
static int daemon_task;
__EXPORT int rw_uart_main(int argc, char *argv[]);
int rw_uart_thread_main(int argc, char *argv[]);
static int uart_init(const char * uart_name);
static int set_uart_baudrate(const int fd, unsigned int baud);
static void usage(const char *reason);
int set_uart_baudrate(const int fd, unsigned int baud)
{
int speed;
switch (baud) {
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
default:
warnx("ERR: baudrate: %d\n", baud);
return -EINVAL;
}
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
tcgetattr(fd, &uart_config);
/* clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* no parity, one stop bit */
uart_config.c_cflag &= ~(CSTOPB | PARENB);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetispeed)\n", termios_state);
return false;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
warnx("ERR: %d (cfsetospeed)\n", termios_state);
return false;
}
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERR: %d (tcsetattr)\n", termios_state);
return false;
}
return true;
}
int uart_init(const char * uart_name)
{
int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);
if (serial_fd < 0) {
err(1, "failed to open port: %s", uart_name);
return false;
}
return serial_fd;
}
static void usage(const char *reason)
{
if (reason) {
fprintf(stderr, "%s\n", reason);
}
fprintf(stderr, "usage: position_estimator_inav {start|stop|status} [param]\n\n");
exit(1);
}
int rw_uart_main(int argc, char *argv[])
{
if (argc < 2) {
usage("[YCM]missing command");
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("[YCM]already running\n");
exit(0);
}
thread_should_exit = false;
daemon_task = px4_task_spawn_cmd("rw_uart",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
rw_uart_thread_main,
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
thread_should_exit = true;
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("[YCM]running");
} else {
warnx("[YCM]stopped");
}
exit(0);
}
usage("unrecognized command");
exit(1);
}
int rw_uart_thread_main(int argc, char *argv[])
{
if (argc < 2) {
errx(1, "[YCM]need a serial port name as argument");
usage("eg:");
}
const char *uart_name = argv[1];
warnx("[YCM]opening port %s", uart_name);
char data = '0';
char buffer[5] = "";
/*
* TELEM1 : /dev/ttyS1
* TELEM2 : /dev/ttyS2
* GPS : /dev/ttyS3
* NSH : /dev/ttyS5
* SERIAL4: /dev/ttyS6
* N/A : /dev/ttyS4
* IO DEBUG (RX only):/dev/ttyS0
*/
int uart_read = uart_init(uart_name);
if(false == uart_read)return -1;
if(false == set_uart_baudrate(uart_read,9600)){
printf("[YCM]set_uart_baudrate is failed\n");
return -1;
}
printf("[YCM]uart init is successful\n");
thread_running = true;
/*初始化資料結構體 */
struct rw_uart_sonar_data_s sonardata;
memset(&sonardata, 0, sizeof(sonardata));
/* 公告主題 */
orb_advert_t rw_uart_sonar_pub = orb_advertise(ORB_ID(rw_uart_sonar), &sonardata);
while(!thread_should_exit){
read(uart_read,&data,1);
if(data == 'R'){
for(int i = 0;i <4;++i){
read(uart_read,&data,1);
buffer[i] = data;
data = '0';
}
strncpy(sonardata.datastr,buffer,4);
sonardata.data = atoi(sonardata.datastr);
//printf("[YCM]sonar.data=%d\n",sonardata.data);
orb_publish(ORB_ID(rw_uart_sonar), rw_uart_sonar_pub, &sonardata);
}
}
warnx("[YCM]exiting");
thread_running = false;
close(uart_read);
fflush(stdout);
return 0;
}
3.2 測試釋出的主題—訂閱主題
測試可以隨便一個啟動的app中進行主題訂閱,然後將訂閱的資料打印出來,看是否是超聲波的資料。這裡測試是在韌體的src/examples
資料夾中的px4_simple_app
應用進行測試的。
- 將
px4_simple_app
應用新增到NuttShell中。Firmware/makefiles/nuttx/config_px4fmu-v2_default.mk
檔案中新增如下內容:
- MODULES += examples/px4_simple_app
- 在
px4_simple_app.c
中程式碼內容:
#include <px4_config.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <string.h>
#include <uORB/uORB.h>
#include "rw_uart/rw_uart_sonar_topic.h"
__EXPORT int px4_simple_app_main(int argc, char *argv[]);
int px4_simple_app_main(int argc, char *argv[])
{
printf("Hello Sky!\n");
/* subscribe to rw_uart_sonar topic */
int sonar_sub_fd = orb_subscribe(ORB_ID(rw_uart_sonar));
/*設定以一秒鐘接收一次,並打印出資料*/
orb_set_interval(sonar_sub_fd, 1000);
bool updated;
struct rw_uart_sonar_data_s sonar;
/*接收資料方式一:start*/
/*
while(true){
orb_check(sonar_sub_fd, &updated);
if (updated) {
orb_copy(ORB_ID(rw_uart_sonar), sonar_sub_fd, &sonar);
printf("[YCM]sonar.data=%d\n",sonar.data);
}
//else printf("[YCM]No soanar data update\n");
}
*/
/*接收資料方式一:end*/
/*接收資料方式二:start*/
/* one could wait for multiple topics with this technique, just using one here */
struct pollfd fds[] = {
{ .fd = sonar_sub_fd, .events = POLLIN },
/* there could be more file descriptors here, in the form like:
* { .fd = other_sub_fd, .events = POLLIN },
*/
};
int error_counter = 0;
for (int i = 0; i < 5; i++) {s
/* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
int poll_ret = poll(fds, 1, 1000);
/* handle the poll result */
if (poll_ret == 0) {
/* this means none of our providers is giving us data */
printf("[px4_simple_app] Got no data within a second\n");
} else if (poll_ret < 0) {
/* this is seriously bad - should be an emergency */
if (error_counter < 10 || error_counter % 50 == 0) {
/* use a counter to prevent flooding (and slowing us down) */
printf("[px4_simple_app] ERROR return value from poll(): %d\n"
, poll_ret);
}
error_counter++;
} else {
if (fds[0].revents & POLLIN) {
/* obtained data for the first file descriptor */
struct rw_uart_sonar_data_s sonar;
/* copy sensors raw data into local buffer */
orb_copy(ORB_ID(rw_uart_sonar), sonar_sub_fd, &sonar);
printf("[px4_simple_app] Sonar data:\t%s\t%d\n",
sonar.datastr,
sonar.data);
}
/* there could be more file descriptors here, in the form like:
* if (fds[1..n].revents & POLLIN) {}
*/
}
}
/*接收資料方式二:end*/
return 0;
}
編譯並刷韌體
- make upload px4fmu-v2_default
在NSH中測試(已加入自啟動指令碼中)
- rw_uart start /dev/ttyS2
- px4_simple_app
3.3 加入系統啟動指令碼
可以加入到光流的自定義啟動指令碼中:/fs/microsd/etc/extras.txt
。這樣隨著系統的自啟動,rw_uart
就會預設啟動了。
# start sonar
rw_uart start /dev/ttyS2