无人系统的远程控制包括遥手持遥控器控制和地面站控制。遥控器是实现无人车、无人机、无人潜航器运动控制的基本部件,用一个高大上点的词叫人在回路控制,或者人机协同控制。也就是将人的意志通过遥控器发送给机器人端,让机器人按照我们想要的动作去执行任务,例如前进后退、调速、调姿、调档等。小型无人系统我们都可以用航模遥控器,它的通信链路如图所示
其实遥控器端的原理很简单,主要有左右两组摇杆(四个通道)以及若干拨码开关。摇杆连接的是电位器,摇杆的不同位置输出不同的电压值,遥控器的控制芯片进行AD采样获取摇杆位置,拨码开关类似,只不过更简单,状态就是0和1,三段开关就是两个电位器组合用就行了。遥控器将获取到的各个通道值通过无线通信发送给接收机。接收机通过三种方式等值输出这些通道值,一是多路PWM,一是PPM信号,一是SBUS信号。PPM信号是调制的PWM信号,就是将多个PWM信号调成一串信号,用同样的方式去解析就能得到各个通道值,SBUS信号是串口通信信号,按照SBUS的通信协议进行解析即可。我们首选SBUS信号,因为它最方便、最省资源。
SBUS全称serial-bus,是一种串口通信协议,广泛应用于航模遥控器(接收机)中。只用一根信号线就能传输多达16通道的数据。
下面终于开始激动人心的写代码环节了,在上一章我提供的正点原子的UCOS-III操作系统工程模板基础上,修改main.c函数,我们首先创建RadioLinkTask——无线通信任务,专门用来解析接收机SBUS信号。
//任务优先级
#define START_TASK_PRIO 3
//任务堆栈大小
#define START_STK_SIZE 128
//任务控制块
OS_TCB StartTaskTCB;
//任务堆栈
CPU_STK START_TASK_STK[START_STK_SIZE];
//任务函数
void start_task(void *p_arg);
//communicate任务
//设置任务优先级
#define COMMUNICATE_TASK_PRIO 5 // SBUS 信号的更新是在串口中断中进行的
//任务堆栈大小
#define COMMUNICATE_STK_SIZE 512
//任务控制块
OS_TCB CommunicateTaskTCB;
//任务堆栈
CPU_STK COMMUNICATE_TASK_STK[COMMUNICATE_STK_SIZE];
//led0任务
void communicate_task(void *p_arg);
int main(void)
{
u8 res;
OS_ERR err;
CPU_SR_ALLOC();
Write_Through(); //Cahce强制透写
MPU_Memory_Protection(); //保护相关存储区域
Cache_Enable(); //打开L1-Cache
Stm32_Clock_Init(432, 25, 2, 9); //设置时钟,216Mhz
HAL_Init(); //初始化HAL库
delay_init(216); //延时初始化
uart1_init(100000); //串口1初始化
uart2_init(115200); //串口2初始化
uart3_init(115200); //串口3初始化
KEY_Init(); //按键初始化
LED_Init(); //初始化LED
OSInit(&err); //初始化UCOSIII
OS_CRITICAL_ENTER(); //进入临界区
//创建开始任务
OSTaskCreate((OS_TCB *)&StartTaskTCB, //任务控制块
(CPU_CHAR *)"start task", //任务名字
(OS_TASK_PTR)start_task, //任务函数
(void *)0, //传递给任务函数的参数
(OS_PRIO)START_TASK_PRIO, //任务优先级
(CPU_STK *)&START_TASK_STK[0], //任务堆栈基地址
(CPU_STK_SIZE)START_STK_SIZE / 10, //任务堆栈深度限位
(CPU_STK_SIZE)START_STK_SIZE, //任务堆栈大小
(OS_MSG_QTY)0, //任务内部消息队列能够接收的最大消息数目,为0时禁止接收消息
(OS_TICK)0, //当使能时间片轮转时的时间片长度,为0时为默认长度,
(void *)0, //用户补充的存储区
(OS_OPT)OS_OPT_TASK_STK_CHK | OS_OPT_TASK_STK_CLR, //任务选项
(OS_ERR *)&err); //存放该函数错误时的返回值
OS_CRITICAL_EXIT(); //退出临界区
OSStart(&err); //开启UCOSIII
while (1)
;
}
//开始任务函数
void start_task(void *p_arg)
{
OS_ERR err;
CPU_SR_ALLOC();
p_arg = p_arg;
CPU_Init();
#if OS_CFG_STAT_TASK_EN > 0u
OSStatTaskCPUUsageInit(&err); //统计任务
#endif
#ifdef CPU_CFG_INT_DIS_MEAS_EN //如果使能了测量中断关闭时间
CPU_IntDisMeasMaxCurReset();
#endif
#if OS_CFG_SCHED_ROUND_ROBIN_EN //当使用时间片轮转的时候
//使能时间片轮转调度功能,设置默认的时间片长度
OSSchedRoundRobinCfg(DEF_ENABLED, 1, &err);
#endif
__HAL_RCC_CRC_CLK_ENABLE(); //使能CRC时钟
GUI_Init(); //STemWin初始化
WM_MULTIBUF_Enable(1); //开启STemWin多缓冲,RGB屏可能会用到
OS_CRITICAL_ENTER(); //进入临界区
//communicate任务 通信任务
OSTaskCreate((OS_TCB *)&CommunicateTaskTCB,
(CPU_CHAR *)"Communicate task",
(OS_TASK_PTR)communicate_task,
(void *)0,
(OS_PRIO)COMMUNICATE_TASK_PRIO,
(CPU_STK *)&COMMUNICATE_TASK_STK[0],
(CPU_STK_SIZE)COMMUNICATE_STK_SIZE / 10,
(CPU_STK_SIZE)COMMUNICATE_STK_SIZE,
(OS_MSG_QTY)0,
(OS_TICK)10,
(void *)0,
(OS_OPT)OS_OPT_TASK_STK_CHK | OS_OPT_TASK_STK_CLR | OS_OPT_TASK_SAVE_FP,
(OS_ERR *)&err);
OS_TaskSuspend((OS_TCB *)&StartTaskTCB, &err); //挂起开始任务
OS_CRITICAL_EXIT(); //退出临界区
}
//通信任务
void communicate_task(void *p_arg)
{
OS_ERR err;
CPU_SR_ALLOC();
char remotor_ready = 0; //遥控器通讯是否准备好
u8 sbus_count = 0;
SBUS_CH.ConnectState = 0;
//等待遥控器通讯正常,否则一直等待。遥控器校正,初值初始化
while (sbus_count < 10)
{
if (SBUS_CH.ConnectState == 1)
{
sbus_count++;
SBUS_CH.ConnectState = 0;
}
LED1_Toggle;
LED0_Toggle;
delay_ms(100);
}
remotor_ready = 1; //遥控器通讯成功
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); //遥控器就绪LED1常亮
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET); //LED0常亮
//读遥控器数据
while (1)
{
delay_ms(10);
}
}
main文件当中在main函数之前定义任务优先级、任务堆栈、堆栈大小、任务函数等,目前来说我们只创建了StartTask和CommunicateTask(代码里面我都写的Communicate,后面不区分CommunicateTask和RadioLinkTask),StartTask是用于创建所有其他任务,它的任务优先级最高。main函数与裸机的main函数一样,首先进行时钟初始化、系统初始化、外设初始化等,不同的是操作系统框架下还要进行操作系统的初始化,之后创建开始任务。开始任务为void start_task(void *p_arg)
,它的任务是创建其他所有任务。后面我们想继续增加新的任务,需要修改的有三处,一是main函数之前定义新任务优先级、任务堆栈、堆栈大小、任务函数等,一处是在void start_task(void *p_arg)
当中调用OSTaskCreate函数来创建新任务,一是在后边定义新的任务函数。
在通信任务(CommunicateTask)中,首先是通过判断遥控器的标志位来判断通信是否正常,连续一段时间通信正常则认为遥控器连接上了,LED灯常亮,进入While(1)循环,也就是我们需要实现的任务部分。暂时空着,后面我们补充。
我们首先实现SBUS通信的驱动程序,主要是串口的驱动。后面我都按照这样的模式写,先实现驱动程序,再写应用程序。 在uart.h和uart.c中增加串口1的相关宏定义与函数:
uart.h:
#ifndef _USART_H
#define _USART_H
#include "sys.h"
#include "stdio.h"
#define USART_REC_LEN 100 //定义最大接收字节数 200
#define RXBUFFERSIZE 1 //缓存大小
//串口1
#define EN_USART1_RX 1 //使能(1)/禁止(0)串口1接收
extern u8 USART1_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.末字节为换行符
extern u16 USART1_RX_STA; //接收状态标记
extern UART_HandleTypeDef UART1_Handler; //UART句柄
extern u8 aRxBuffer1[RXBUFFERSIZE];//HAL库USART接收Buffer
void uart1_init(u32 bound);
#endif
uart.c:
#include "usart.h"
#include "sys.h"
#include <iwdg.h>
#include "string.h"
#include "sbus.h"
//如果使用os,则包括下面的头文件即可.
#if SYSTEM_SUPPORT_OS
#include "includes.h" //os 使用
#endif
#if 1
#pragma import(__use_no_semihosting)
//标准库需要的支持函数
struct __FILE
{
int handle;
};
FILE __stdout;
//定义_sys_exit()以避免使用半主机模式
void _sys_exit(int x)
{
x = x;
}
int fputc(int ch, FILE *f)
{
while ((USART1->ISR & 0X40) == 0)
; //循环发送,直到发送完毕
USART1->TDR = (u8)ch;
return ch;
}
#endif
u8 USART1_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.
u16 USART1_RX_STA = 0; //接收状态标记
u8 aRxBuffer1[RXBUFFERSIZE]; //HAL库使用的串口接收缓冲
UART_HandleTypeDef UART1_Handler; //UART句柄
//初始化IO 串口1
//bound:波特率
void uart1_init(u32 bound)
{
//UART 初始化设置
UART1_Handler.Instance = USART1; //USART1
UART1_Handler.Init.BaudRate = bound; //波特率
UART1_Handler.Init.WordLength = UART_WORDLENGTH_9B; //字长为8位数据格式
UART1_Handler.Init.StopBits = UART_STOPBITS_1; //一个停止位
UART1_Handler.Init.Parity = UART_PARITY_EVEN; //无奇偶校验位
UART1_Handler.Init.HwFlowCtl = UART_HWCONTROL_NONE; //无硬件流控
UART1_Handler.Init.Mode = UART_MODE_TX_RX; //收发模式
HAL_UART_Init(&UART1_Handler); //HAL_UART_Init()会使能UART1
HAL_UART_Receive_IT(&UART1_Handler, (u8 *)aRxBuffer1, RXBUFFERSIZE); //该函数会开启接收中断:标志位UART_IT_RXNE,并且设置接收缓冲以及接收缓冲接收最大数据量
}
//UART底层初始化,时钟使能,引脚配置,中断配置
//此函数会被HAL_UART_Init()调用
//huart:串口句柄
void HAL_UART_MspInit(UART_HandleTypeDef *huart)
{
//GPIO端口设置
GPIO_InitTypeDef GPIO_Initure;
if (huart->Instance == USART1) //如果是串口1,进行串口1 MSP初始化
{
__HAL_RCC_GPIOA_CLK_ENABLE(); //使能GPIOA时钟
__HAL_RCC_USART1_CLK_ENABLE(); //使能USART1时钟
GPIO_Initure.Pin = GPIO_PIN_9; //PA9
GPIO_Initure.Mode = GPIO_MODE_AF_PP; //复用推挽输出
GPIO_Initure.Pull = GPIO_PULLUP; //上拉
GPIO_Initure.Speed = GPIO_SPEED_FAST; //高速
GPIO_Initure.Alternate = GPIO_AF7_USART1; //复用为USART1
HAL_GPIO_Init(GPIOA, &GPIO_Initure); //初始化PA9
GPIO_Initure.Pin = GPIO_PIN_10; //PA10
HAL_GPIO_Init(GPIOA, &GPIO_Initure); //初始化PA10
#if EN_USART1_RX
HAL_NVIC_EnableIRQ(USART1_IRQn); //使能USART1中断通道
HAL_NVIC_SetPriority(USART1_IRQn, 3, 2); //抢占优先级3,子优先级3
#endif
}
}
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
int i;
while (huart->Instance == USART1) //如果是串口1
{
USART1_RX_BUF[USART1_RX_STA] = aRxBuffer1[0];
if (USART1_RX_STA == 0 && USART1_RX_BUF[USART1_RX_STA] != 0x0F) break; //帧头不对,丢掉
USART1_RX_STA++;
if (USART1_RX_STA > USART_REC_LEN) USART1_RX_STA = 0; ///接收数据错误,重新开始接收
if (USART1_RX_BUF[0] == 0x0F && USART1_RX_STA == 25) //接受完一帧数据
{
update_sbus(USART1_RX_BUF);
for (i = 0; i<25; i++)
{
USART1_RX_BUF[i] = 0;
}
USART1_RX_STA = 0;
#ifdef ENABLE_IWDG
IWDG_Feed(); //喂狗 //超过时间没有收到遥控器的数据会复位
#endif
}
break;
}
}
//串口1中断服务程序
void USART1_IRQHandler(void)
{
u32 timeout = 0;
u32 maxDelay = 0x1FFFF;
#if SYSTEM_SUPPORT_OS //使用OS
OSIntEnter();
#endif
HAL_UART_IRQHandler(&UART1_Handler); //调用HAL库中断处理公用函数
timeout = 0;
while (HAL_UART_GetState(&UART1_Handler) != HAL_UART_STATE_READY) //等待就绪
{
timeout++; 超时处理
if (timeout > maxDelay)
break;
}
timeout = 0;
while (HAL_UART_Receive_IT(&UART1_Handler, (u8 *)aRxBuffer1, RXBUFFERSIZE) != HAL_OK) //一次处理完成之后,重新开启中断并设置RxXferCount为1
{
timeout++; //超时处理
if (timeout > maxDelay)
break;
}
#if SYSTEM_SUPPORT_OS //使用OS
OSIntExit();
#endif
}
到这里我们实现了串口1的驱动程序,按照SBUS通信的配置将串口1设置成数据位8,偶校验,波特率100k(在main函数里面调用uart1_init(100000)
),串口1 的中断函数里面我们调用update_sbus(USART1_RX_BUF)
,以帧为单位(一帧25个字节)更新SBUS信号,它是自定义函数,原型为u8 update_sbus(u8 *buf)
,在sbus.c里面定义,sbus.h和sbus.c的内容如下:
sbus.h:
#ifndef __SBUS_H
#define __SBUS_H
#include "sys.h"
#define RADIOLINK
#define SBUS_FRAME_SIZE 25
#define SBUS_INPUT_CHANNELS 16
#ifdef RADIOLINK
#define SBUS_RANGE_MIN 300.0f
#define SBUS_RANGE_MAX 1700.0f
#define SBUS_TARGET_MIN 1000.0f
#define SBUS_TARGET_MAX 2000.0f
#define DEAD_RANGE_MIN 960 //死区
#define DEAD_RANGE_MAX 1040
#define SBUS_RANGE_MIDDLE 1000.0f
#define SBUS_CONNECT_FLAG 0x00
#endif
#define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
#define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
//低速与高速模式
#define LOW_SPEED 0
#define HIGH_SPEED 1
//定深与手动模式
#define HAND_MODE 0
#define DEPTH_MODE 1
// IMU 的数据来源
#define JY901 0
#define HT905 1
#define JY901_HT905 2
// 一键起飞、一键降落
#define ONEKEY_LANDING 0
#define ONEKEY_TAKEOFF 1
// 定深模式使能、失能
#define HOLD_DISABLE 0
#define HOLD_ENABLE 1
//右手X:方向 CH1 Y:油门 CH2
//左手X:滚转 CH4 Y:深度 CH3
#define YAW 1
#define THROTTLE 2
#define Z_SPEED 2
#define PITCH 3
#define FORWARD_SPEED 3
#define ROLL 4
#define SPEED_MODE 6
#define PWM_LEFT 7
#define PWM_RIGHT 8
#define CARRY_MODE 9
#define IMU_MODE 10
#define ONEKEY_UP_AND_DOWN 11 // 一键起飞和着陆按钮
#define ALTHOLD_ENABLE 12
extern int command[20]; //遥控器数据
typedef struct
{
uint16_t signal[25];
uint16_t CH1;//通道1数值
uint16_t CH2;//通道2数值
uint16_t CH3;//通道3数值
uint16_t CH4;//通道4数值
uint16_t CH5;//通道5数值
uint16_t CH6;//通道6数值
uint16_t CH7;//通道7数值
uint16_t CH8;//通道8数值
uint16_t CH9;//通道9数值
uint16_t CH10;//通道10数值
uint16_t CH11;//通道10数值
uint16_t CH12;//通道10数值
uint16_t CH13;//通道10数值
uint16_t CH14;//通道10数值
uint16_t CH15;//通道10数值
uint16_t CH16;//通道10数值
uint8_t ConnectState;//遥控器与接收器连接状态 0=未连接,1=正常连接
}SBUS_CH_Struct;
extern SBUS_CH_Struct SBUS_CH;
//SBUS信号解析相关函数
u8 update_sbus(u8 *buf);
u16 sbus_to_pwm(u16 sbus_value);
float sbus_to_Range(u16 sbus_value, float p_min, float p_max);
#endif
sbus.c:
#include "sbus.h"
SBUS_CH_Struct SBUS_CH;
int command[20]; //遥控器数据
/*
[startbyte] [data1][data2]…[data22][flags][endbyte]
startbyte=0x0f;
endbyte=0x00;
flags标志位是用来检测控制器与遥控器是否断开的标志位。
flags=1:控制器与接收器保持连接
flags=0:控制器与接收器断开
*/
//将sbus信号转化为通道值
u8 update_sbus(u8 *buf)
{
int i;
for (i=0;i<25;i++)
SBUS_CH.signal[i] = buf[i];
if (buf[23] == SBUS_CONNECT_FLAG)
{
SBUS_CH.ConnectState = 1;
SBUS_CH.CH1 = ((int16_t)buf[ 1] >> 0 | ((int16_t)buf[ 2] << 8 )) & 0x07FF;
SBUS_CH.CH2 = ((int16_t)buf[ 2] >> 3 | ((int16_t)buf[ 3] << 5 )) & 0x07FF;
SBUS_CH.CH3 = ((int16_t)buf[ 3] >> 6 | ((int16_t)buf[ 4] << 2 ) | (int16_t)buf[ 5] << 10 ) & 0x07FF;
SBUS_CH.CH4 = ((int16_t)buf[ 5] >> 1 | ((int16_t)buf[ 6] << 7 )) & 0x07FF;
SBUS_CH.CH5 = ((int16_t)buf[ 6] >> 4 | ((int16_t)buf[ 7] << 4 )) & 0x07FF;
SBUS_CH.CH6 = ((int16_t)buf[ 7] >> 7 | ((int16_t)buf[ 8] << 1 ) | (int16_t)buf[9] << 9 ) & 0x07FF;
SBUS_CH.CH7 = ((int16_t)buf[ 9] >> 2 | ((int16_t)buf[10] << 6 )) & 0x07FF;
SBUS_CH.CH8 = ((int16_t)buf[10] >> 5 | ((int16_t)buf[11] << 3 )) & 0x07FF;
SBUS_CH.CH9 = ((int16_t)buf[12] << 0 | ((int16_t)buf[13] << 8 )) & 0x07FF;
SBUS_CH.CH10 = ((int16_t)buf[13] >> 3 | ((int16_t)buf[14] << 5 )) & 0x07FF;
SBUS_CH.CH11 = ((int16_t)buf[14] >> 6 | ((int16_t)buf[15] << 2 ) | (int16_t)buf[16] << 10 ) & 0x07FF;
SBUS_CH.CH12 = ((int16_t)buf[16] >> 1 | ((int16_t)buf[17] << 7 )) & 0x07FF;
SBUS_CH.CH13 = ((int16_t)buf[17] >> 4 | ((int16_t)buf[18] << 4 )) & 0x07FF;
SBUS_CH.CH14 = ((int16_t)buf[18] >> 7 | ((int16_t)buf[19] << 1 ) | (int16_t)buf[20] << 9 ) & 0x07FF;
SBUS_CH.CH15 = ((int16_t)buf[20] >> 2 | ((int16_t)buf[21] << 6 )) & 0x07FF;
SBUS_CH.CH16 = ((int16_t)buf[21] >> 5 | ((int16_t)buf[22] << 3 )) & 0x07FF;
return 1;
}
else
{
SBUS_CH.ConnectState = 0;
return 0;
}
}
u16 sbus_to_pwm(u16 sbus_value)
{
float pwm;
pwm = (float)SBUS_TARGET_MIN + (float)(sbus_value - SBUS_RANGE_MIN) * SBUS_SCALE_FACTOR;
// 1000 300 1000/1400
if (pwm > 2000) pwm = 2000;
if (pwm < 1000) pwm = 1000;
return (u16)pwm;
}
//将sbus信号通道值转化为特定区间的数值 [p_min,p_max]
float sbus_to_Range(u16 sbus_value, float p_min, float p_max)
{
float p;
p = p_min + (float)(sbus_value - SBUS_RANGE_MIN) * (p_max-p_min)/(float)(SBUS_RANGE_MAX - SBUS_RANGE_MIN);
if (p > p_max) p = p_max;
if (p < p_min) p = p_min;
return p;
}
在sbus.h中我们定义了一个SBUS_CH_Struct
的结构体类型,并定义了一个该类型的结构体SBUS_CH
,用来存放SBUS的各个通道数据值以及连接状态,u8 update_sbus(u8 *buf)
功能就是从编码的sbus信号中解析出16个通道的数值以及遥控器连接标志。u16 sbus_to_pwm(u16 sbus_value)
与float sbus_to_Range(u16 sbus_value, float p_min, float p_max)
都是字面意思,将SBUS的信号值转化为特定区间的值,就是一个函数映射关系。转化为PWM的值就是1000-2000。
这里我们还定义了一个 数组 int command[20]
,这个数组非常重要,用它来存放遥控器发送的命令。注意是命令不是数据,SBUS_CH存放的是各个通道值,我们通过判断各个通道的值就可以解析遥控器想要传达的命令,请看下面的应用程序如何实现这种转换。
到这里我们已经实现了遥控器的SBUS信号解析,在前面的main函数中修改CommunicateTask
函数:
//通信任务
void communicate_task(void *p_arg)
{
OS_ERR err;
CPU_SR_ALLOC();
char remotor_ready = 0; //遥控器通讯是否准备好
u8 sbus_count = 0;
SBUS_CH.ConnectState = 0;
//等待遥控器通讯正常,否则一直等待。遥控器校正,初值初始化
while (sbus_count < 10)
{
if (SBUS_CH.ConnectState == 1)
{
sbus_count++;
SBUS_CH.ConnectState = 0;
}
LED1_Toggle;
LED0_Toggle;
delay_ms(100);
}
remotor_ready = 1; //遥控器通讯成功
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); //遥控器就绪LED1常亮
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET); //LED0常亮
//读遥控器数据
while (1)
{
printf("遥控器的通道值为: CH1 %d CH2 %d CH3 %d CH4 %d CH5 %d CH6 %d CH7 %d CH8 %d",SBUS_CH.CH1,SBUS_CH.CH2,SBUS_CH.CH3,SBUS_CH.CH4,SBUS_CH.CH5,SBUS_CH.CH6,SBUS_CH.CH7,SBUS_CH.CH8)
delay_ms(10);
}
}
增加了一行代码printf("遥控器的通道值为: CH1 %d CH2 %d CH3 %d CH4 %d CH5 %d CH6 %d CH7 %d CH8 %d",SBUS_CH.CH1,SBUS_CH.CH2,SBUS_CH.CH3,SBUS_CH.CH4,SBUS_CH.CH5,SBUS_CH.CH6,SBUS_CH.CH7,SBUS_CH.CH8)
,用USB-TTL工具连接UART的TX口(RX口已经连接了接收机),电脑端注意将配置改为100k波特率与偶校验。此时就可以看到打印出来的SBUS通道的数值了。但是我们需要二次处理这些数据,所以修改上面的while(1)函数:
//读遥控器数据
while (1)
{
if (SBUS_CH.CH5 < 400) //选择IMU数据来源
command[IMU_MODE] = JY901;
else if (SBUS_CH.CH5 < 1100)
command[IMU_MODE] = HT905;
else
command[IMU_MODE] = HT905;
if (SBUS_CH.CH6 < 1000) //速度档位
command[SPEED_MODE] = LOW_SPEED;
else
command[SPEED_MODE] = HIGH_SPEED;
if (SBUS_CH.CH10 < 1000) //选择定深模式(定高)与手动模式
command[CARRY_MODE] = HAND_MODE;
else
command[CARRY_MODE] = DEPTH_MODE;
if (SBUS_CH.CH9 < 1000) //定高模式时 油门使能 按钮,为disable油门不输出,机器人不动
command[ALTHOLD_ENABLE] = HOLD_DISABLE;
else
command[ALTHOLD_ENABLE] = HOLD_ENABLE;
// 左手油门
command[THROTTLE] = sbus_to_pwm(SBUS_CH.CH3);
command[YAW] = sbus_to_pwm(SBUS_CH.CH4);
command[ROLL] = sbus_to_pwm(SBUS_CH.CH1);
command[PITCH] = sbus_to_pwm(SBUS_CH.CH2);
// | 四轴油门(手动) | 四轴俯仰(手动)
// | 上下速度(定高) | 前后速度(定高)
// | |
//——————————|————————— YAW ————————————|———————————— ROLL
// | |
// | |
// | |
// 手动模式用 旋钮通道 控制油门
command[PWM_LEFT] = sbus_to_pwm(SBUS_CH.CH7); // 控制舵机
command[PWM_RIGHT] = sbus_to_pwm(SBUS_CH.CH8); // 控制波动鳍电机
delay_ms(10);
}
这里我们将CH1-CH4四个遥感通道的值转化为PWM值(1000-2000),这四个主要通道将用来操纵机器人的前后左右上下等机动运动。将其他二段开关或三段开关的值转变为相应的命令模式,这些在后面都会用到,比如用来切换速度档位、定深与手动模式等。当然你可以自定义各种模式,可以将各种模式对应到不同的通道,神奇吗?想一想买过的一些玩具,包括智能车、无人机,是不是告诉过你遥控器按哪个按钮可以实现什么功能,原理就是这样的,很简单。