|
基于 CPKCOR-RA8D1 开发板的 RTK 智能车开结合实时动态定位(RTK)技术与嵌入式控制,实现高精度导航与运动控制。核心处理器选择RA8D1 ,搭载ARM Cortex-M85内核,主频高达 240MHz,是当前 Cortex-M 系列中针对实时控制优化的高性能架构。相比传统 M4/M7 内核:整数运算性能提升约 30%,支持单周期 MAC(乘法累加)操作,可快速处理电机 PID 控制、路径规划中的矩阵运算(如坐标转换、航向角计算)。集成双精度 FPU(浮点运算单元),直接硬件加速 RTK 定位中的坐标转换(如 WGS84 到 UTM 的投影计算)、姿态解算(MPU6050 的欧拉角转换)等浮点密集型任务,避免软件模拟带来的延迟。 单片机资源丰富,多通道 UART:支持至少 6 路硬件 UART,可同时连接 RTK 模块(ZED-F9P)、蓝牙(HC-05)、Wi-Fi(ESP8266)、激光雷达(若扩展)等,且支持高达 3Mbps 波 特率,确保 RTK 差分数据(RTCM)和传感器数据无丢包传输。 高精度定时器(GPT):内置多通道 32 位定时器,支持编码器接口模式(Encoder Mode),可直接连接电机霍尔编码器,通过硬件计数实现转速测量(精度达 ±1 脉冲),比软件计数减少 ±5% 的误差。 PWM 模块:支持多达 12 路独立 PWM 输出,且支持死区控制和互补输出,可直接驱动 H 桥电机驱动器(TB6612FNG),避免电机换向时的短路风险。 I²C/SPI 接口:硬件 I²C 支持 1Mbps 速率,可高效连接 MPU6050(姿态传感器);SPI 支持 40MHz 速率,可扩展高速存储(如 SD 卡记录轨迹数据)或 Wi-Fi 模块。 一、开发目标与核心需求1. 核心目标:实现智能车在厘米级定位精度下的自主导航、路径规划与运动控制。 2. 关键指标: ◦ 定位精度:RTK 模式下水平 ±1cm,垂直 ±2cm; ◦ 控制响应:电机调速响应时间<100ms; ◦ 导航模式:支持定点巡航、路径跟踪、避障绕行; ◦ 环境适应性:适应室内外平整路面,支持蓝牙 / Wi-Fi 远程监控。 二、硬件系统设计1. 核心控制模块• 主控制器:CPKCOR-RA8D1 开发板(基于瑞萨 RA8D1 MCU,ARM Cortex-M85 内核,主频 240MHz,支持 FPU/MPU,丰富外设接口)。 • 功能扩展:利用开发板的 GPIO、UART、SPI、I²C、PWM 接口,连接传感器与执行器。 系统结构: 2. RTK 定位模块• RTK 模块:选用北斗 + GPS 双模模块(思南RTK模组),支持 RTK 解算,通过 UART 与 RA8D1 通信(波特率115200)。 • 差分信号源: ◦ 户外:接入 NTRIP(Networked Transport of RTCM via Internet Protocol)服务器,通过 4G 模块(如EC20)获取差分数据; ◦ 室内 / 小范围:搭配本地基准站,通过 LoRa 模块传输差分信号。 • 天线:高精度 GNSS 有源天线(放置于车顶,避免遮挡)。 3. 运动控制模块• 驱动方式:两轮差速驱动(左右轮独立控制转向)。 • 电机与驱动器: ◦ 电机:直流减速电机(带霍尔编码器,如 TT 电机,转速 300rpm,减速比 1:48); ◦ 驱动器:H 桥电机驱动芯片(如 TB6612FNG,支持 PWM 调速,通过 GPIO 与 RA8D1 连接)。 • 编码器接口:RA8D1 的定时器(TIM)捕获编码器脉冲,用于速度闭环控制(PID 调节)。
4. 环境感知模块• 避障传感器: ◦ 超声波传感器(HC-SR04,检测距离 2-400cm,用于中距离避障); ◦ 红外接近传感器(GP2Y0A21YK,检测距离 10-80cm,用于短距离防碰撞); ◦ (可选)激光雷达(如 RPLIDAR A1,通过 UART/SPI 连接,用于环境地图构建)。 • 姿态传感器:MPU6050(加速度 + 陀螺仪,I²C 接口),辅助判断车身倾斜状态,修正运动控制。 5. 通信与电源模块• 无线通信: ◦ 蓝牙模块(ESP32,UART 接口,用于近距离调试与控制); ◦ Wi-Fi 模块(ESP8266,SPI 接口,用于远程数据上传与指令接收)。 • 电源系统: ◦ 主电源:12V 锂电池(容量 5000mAh,持续供电≥2 小时); ◦ 稳压电路: ▪ 5V 输出(给 RTK 模块、传感器、通信模块供电,采用 LM1117-5V); ▪ 3.3V 输出(给 RA8D1 开发板供电,采用 AMS1117-3.3)。 三、软件系统设计 瑞萨官方提供对RT-Thread、FreeRTOS等实时操作系统的完整支持,包括外设驱动库(FSP,Flexible Software Package),可快速实现多任务调度(如电机控制、传感器采集、导航算法的并行运行),避免底层驱动开发的重复劳动。基于FreeRTOS/RT-Thread 实时操作系统(适配 RA8D1),采用模块化设计,确保任务调度与实时性。 1. 系统架构• 内核层:RTOS内核(任务管理、定时器、信号量、消息队列)。 • 驱动层:硬件外设驱动(UART、SPI、I²C、PWM、GPIO)及传感器驱动(GNSS、编码器、MPU6050 等)。 • 应用层:功能模块(定位解析、运动控制、路径规划、避障逻辑、通信交互)。 2. 核心任务设计(优先级从高到低) 任务名称 | | | | | | | | | | | | | 解析 GNSS 数据(GGA/RMC 消息),获取经纬度 | | | | | | | | 蓝牙 / Wi-Fi 数据收发(指令接收、状态上传) | | | 3. 关键算法实现
- /* 坐标与姿态数据结构 */
- typedef struct {
- double lat; // 纬度(度)
- double lon; // 经度(度)
- float alt; // 海拔(米)
- float heading; // 航向角(度,0-360)
- float speed; // 移动速度(米/秒)
- uint8_t fix_type; // 定位类型(0=无效,1=单点,2=RTK固定)
- } gps_data_t;
- /* 电机控制参数 */
- typedef struct {
- int16_t target_speed; // 目标速度(PWM占空比,-1000~1000)
- int16_t current_speed; // 当前速度(编码器计算)
- int32_t encoder_cnt; // 编码器累计脉冲
- // PID参数
- float kp;
- float ki;
- float kd;
- float err; // 当前误差
- float err_last; // 上一次误差
- float err_sum; // 误差积分
- } motor_t;
- /* 全局数据 */
- gps_data_t g_gps_data = {0}; // RTK定位数据
- motor_t g_motors[2] = { // 左右电机(0=左,1=右)
- {.kp=5.0, .ki=0.1, .kd=0.5},
- {.kp=5.0, .ki=0.1, .kd=0.5}
- };
- float g_obstacle_dist = 0; // 障碍物距离(厘米)
• RTK 定位解析: ◦ 解析 ublox 输出的 RTCM 差分数据与 NMEA-0183 协议(GGA 消息提取经纬度、海拔、定位质量;RMC 消息提取速度、航向)。 ◦ 坐标转换:将 WGS84 经纬度转换为本地平面坐标(如 UTM 投影),简化路径计算。 RTK数据解析: - #include <rtthread.h>
- #include <rtdevice.h>
- #define UART_GPS "uart2" // RA8D1连接RTK模块的UART端口
- static rt_device_t g_uart_gps;
- /* NMEA协议解析(GGA消息示例) */
- static void nmea_parse_gga(const char *msg, gps_data_t *gps) {
- char *token = strtok((char*)msg, ",");
- int field = 0;
- while (token != RT_NULL) {
- switch(field) {
- case 2: gps->lat = atof(token); // 纬度(ddmm.mmmm)
- case 3: if (*token == 'S') gps->lat = -gps->lat;
- case 4: gps->lon = atof(token); // 经度(dddmm.mmmm)
- case 5: if (*token == 'W') gps->lon = -gps->lon;
- case 6: gps->fix_type = atoi(token); // 定位类型
- case 9: gps->alt = atof(token); // 海拔
- default: break;
- }
- token = strtok(RT_NULL, ",");
- field++;
- }
- // 转换为度分格式(dd.dddd)
- gps->lat = (int)(gps->lat / 100) + (gps->lat - (int)(gps->lat / 100)*100)/60;
- gps->lon = (int)(gps->lon / 100) + (gps->lon - (int)(gps->lon / 100)*100)/60;
- }
- /* UART接收回调函数 */
- static rt_err_t gps_uart_rx_cb(rt_device_t dev, rt_size_t size) {
- static char gps_buf[256] = {0};
- static uint16_t buf_len = 0;
- rt_size_t len = rt_device_read(dev, 0, &gps_buf[buf_len], 256 - buf_len);
- if (len > 0) {
- buf_len += len;
- // 查找换行符(NMEA消息结束标志)
- if (strstr(gps_buf, "\r\n")) {
- if (strstr(gps_buf, "$GNGGA")) { // 北斗+GPS双模GGA消息
- nmea_parse_gga(gps_buf, &g_gps_data);
- }
- // 清空缓冲区
- rt_memset(gps_buf, 0, buf_len);
- buf_len = 0;
- }
- }
- return RT_EOK;
- }
- /* 初始化RTK模块 */
- void rtk_init(void) {
- g_uart_gps = rt_device_find(UART_GPS);
- RT_ASSERT(g_uart_gps != RT_NULL);
- // 配置UART参数(38400波特率,8N1)
- struct serial_configure cfg = RT_SERIAL_CONFIG_DEFAULT;
- cfg.baud_rate = BAUD_RATE_38400;
- rt_device_control(g_uart_gps, RT_DEVICE_CTRL_CONFIG, &cfg);
- // 设置接收回调
- rt_device_set_rx_indicate(g_uart_gps, gps_uart_rx_cb);
- rt_device_open(g_uart_gps, RT_DEVICE_OFLAG_RDWR | RT_DEVICE_FLAG_INT_RX);
- }
• 运动控制算法: ◦ 速度闭环:根据编码器反馈计算实际转速,通过 PID 调节 PWM 占空比(比例系数 Kp=5.0,积分 Ki=0.1,微分 Kd=0.5)。 ◦ 转向控制:基于差速模型,目标航向与当前航向的偏差 Δθ,通过左右轮速度差实现转向(Δv = Kθ×Δθ,Kθ 为转向系数)。 • 路径规划与导航: ◦ 直线跟踪:计算当前位置到目标点的距离与方位角,通过 PID 调节转向(距离误差→速度,方位角误差→转向)。 ◦ 避障逻辑:当传感器检测到障碍物(距离<设定阈值),触发绕行模式(暂停原路径,转向 90° 后前进,避障后回归路径)。 - #define PWM_MOTOR_LEFT "pwm2" // 左电机PWM通道
- #define PWM_MOTOR_RIGHT "pwm3" // 右电机PWM通道
- #define ENCODER_LEFT TIM3 // 左编码器定时器
- #define ENCODER_RIGHT TIM4 // 右编码器定时器
- /* 编码器计数读取 */
- static int32_t encoder_get_count(TIM_HandleTypeDef *htim) {
- int32_t cnt = htim->Instance->CNT;
- htim->Instance->CNT = 0; // 清零计数
- return cnt;
- }
- /* PID速度调节 */
- static int16_t motor_pid_calc(motor_t *motor) {
- motor->err = motor->target_speed - motor->current_speed;
- motor->err_sum += motor->err;
- // 积分限幅(防止饱和)
- if (motor->err_sum > 1000) motor->err_sum = 1000;
- if (motor->err_sum < -1000) motor->err_sum = -1000;
- // PID计算
- float output = motor->kp * motor->err
- + motor->ki * motor->err_sum
- + motor->kd * (motor->err - motor->err_last);
- motor->err_last = motor->err;
- // 输出限幅(PWM范围)
- if (output > 1000) output = 1000;
- if (output < -1000) output = -1000;
- return (int16_t)output;
- }
- /* 电机PWM控制 */
- static void motor_set_pwm(int16_t left_pwm, int16_t right_pwm) {
- rt_pwm_set(PWM_MOTOR_LEFT, 10000, abs(left_pwm)); // 周期10ms
- rt_pwm_set(PWM_MOTOR_RIGHT, 10000, abs(right_pwm));
- // 控制方向(通过GPIO电平)
- rt_pin_write(PIN_MOTOR_LEFT_DIR, left_pwm > 0 ? 1 : 0);
- rt_pin_write(PIN_MOTOR_RIGHT_DIR, right_pwm > 0 ? 1 : 0);
- }
- /* 电机控制任务(10ms周期) */
- static void motor_task(void *parameter) {
- // 初始化PWM与编码器
- rt_pwm_init(PWM_MOTOR_LEFT);
- rt_pwm_init(PWM_MOTOR_RIGHT);
- HAL_TIM_Encoder_Start(&htim3, TIM_CHANNEL_ALL); // 启动编码器
- HAL_TIM_Encoder_Start(&htim4, TIM_CHANNEL_ALL);
- while (1) {
- // 读取编码器计算当前速度(脉冲/10ms → 转换为PWM对应速度)
- g_motors[0].current_speed = encoder_get_count(&htim3) * 0.8; // 系数校准
- g_motors[1].current_speed = encoder_get_count(&htim4) * 0.8;
- // 计算PID输出并控制电机
- int16_t left_pwm = motor_pid_calc(&g_motors[0]);
- int16_t right_pwm = motor_pid_calc(&g_motors[1]);
- motor_set_pwm(left_pwm, right_pwm);
- rt_thread_mdelay(10); // 10ms周期
- }
- }
路径规划 - /* 目标点(示例:UTM坐标,单位米) */
- static const float target_x = 10.0; // 目标X坐标
- static const float target_y = 5.0; // 目标Y坐标
- /* WGS84经纬度转本地平面坐标(简化版UTM) */
- static void wgs84_to_utm(gps_data_t *gps, float *x, float *y) {
- // 基于参考点(原点)的相对坐标计算
- static const float ref_lat = 30.0; // 本地原点纬度
- static const float ref_lon = 120.0; // 本地原点经度
- *x = (gps->lon - ref_lon) * 111319.5; // 经度1度≈111319.5米
- *y = (gps->lat - ref_lat) * 111319.5;
- }
- /* 计算到目标点的距离与方位角 */
- static void calc_target_error(float *distance, float *angle) {
- float curr_x, curr_y;
- wgs84_to_utm(&g_gps_data, &curr_x, &curr_y);
- // 距离(米)
- *distance = sqrtf(powf(target_x - curr_x, 2) + powf(target_y - curr_y, 2));
- // 方位角(度,相对于正北)
- *angle = atan2f(target_x - curr_x, target_y - curr_y) * 180 / M_PI;
- if (*angle < 0) *angle += 360;
- }
- /* 路径跟踪任务(200ms周期) */
- static void navigation_task(void *parameter) {
- float distance, angle;
- float angle_err; // 航向误差
- while (1) {
- // 避障逻辑:若检测到障碍物(距离<50cm),暂停路径跟踪
- if (g_obstacle_dist < 50 && g_obstacle_dist > 0) {
- g_motors[0].target_speed = 0;
- g_motors[1].target_speed = 0;
- rt_thread_mdelay(500); // 停车
- // 右转绕行(左轮正转,右轮反转)
- g_motors[0].target_speed = 300;
- g_motors[1].target_speed = -300;
- rt_thread_mdelay(1000); // 转向90度
- continue;
- }
- // 正常路径跟踪
- calc_target_error(&distance, &angle);
- // 到达目标点(误差<0.1米)
- if (distance < 0.1) {
- g_motors[0].target_speed = 0;
- g_motors[1].target_speed = 0;
- rt_kprintf("到达目标点!\n");
- rt_thread_suspend(rt_thread_self());
- }
- // 计算航向误差(当前航向与目标方位角的差)
- angle_err = angle - g_gps_data.heading;
- if (angle_err > 180) angle_err -= 360;
- if (angle_err < -180) angle_err += 360;
- // 速度控制:距离越近速度越慢
- int16_t base_speed = 300 + (distance > 5 ? 200 : 0); // 最大500
- // 转向控制:航向误差决定左右轮速度差
- int16_t diff_speed = angle_err * 5; // 转向系数
- g_motors[0].target_speed = base_speed + diff_speed;
- g_motors[1].target_speed = base_speed - diff_speed;
- rt_thread_mdelay(200); // 200ms周期
- }
- }
|