基于ROS与YOLOv3的智能采购机器人设计(智能车创意组-讯飞智慧生活组)
本文提出了一种在Ubuntu中基于ROS操作系统的智能采购机器人控制系统 的设计,重点实现了自主导航和图像识别的设计,通过对智能采购机器人在模拟 城市场景中自主导航、智能避障、货品拣选需求和控制系统的分析,完成了智能 采购机器人的系统平台搭建和程序设计。
1.智能采购机器人控制系统总体设计方案如下所示:

(1)外部服务器模块:外部服务器模块是一台笔记本电脑,电脑PC端基于 Ubuntu18.04 环境安装 melodic 版本的 ROS 系统,和智能采购机器人主控制系 统间通过局域网进行通信,主要用于智能采购机器人定位导航系统的远程开发、 远程调试与监控。
(2)机器人主控制模块:采用主从控制作为智能采购机器人控制系统方式, 上位机承担高层次的策略制定与协同调节任务,下位机分布式控制主要实现多机 器人系统间协同作业的控制,通过分布式控制能够提高多机器人工作时的效率。 选择上位机Jetson nano 作为主控制器,用来处理机器人控制过程中的数据和运动,将处理后的数据信息发送给下位机。传感器部分由激光雷达和广角相机组成, 其中激光雷达与上位机通过UART连接,广角相机与上位机通过USB连接。
(3)底层控制模块:选择下位机STM32F407作为主控制器,进行简单的数据处理和基本的运动控制,驱动智能采购机器人完成上位机指定动作,下位机 STM32F407 采集的数据同时反馈给上位机计算核心再进行处理。底层控制模块 主要是通过STM32F407的直流电机接口控制带霍尔编码器的无刷电机,并且将电机的编码器数据反馈给STM32F407,再由STM32F407将经过解析的编码器 数据发送给智能采购机器人的主控制器。
本设计重点在于开发智能采购机器人——ROS系统及图像识别功能,以实现以下采购任务:
(1)通过激光雷达和目标点坐标,可以完成自主的路径规划,将具体的行 动信息发送给下位机,通过驱动麦克纳姆轮,到达目的地。
(2)到达目的地后,基于广角相机采集到的图像,在上位机中完成智能匹 配与识别,完成货品的拣选与路标识别。
(3)同时在第一项和第二项任务进行的过程中,还可以通过雷达迭代周边 数据信息,实时对场地中的障碍物进行避障。
2.智能采购机器人—ROS系统结构
智能采购机器人的处理器由上位机GPU嵌入式计算核心和MCU下位机计 算核心两部分组成,选用一款英伟达 Jetson 系列中的嵌入式板卡 Jetson nano作为上位机处理核心,选用一块 STM32F407 系列的 MCU作为下位机处理核心。 使用串口USAT与激光雷达相连接,1路USB与广角相机相连接,1路USB 与下位机STM32F407连接。

STM32F407 系列的MCU的板载预留了许多的接口资源,还包含了一些常用外设,其中UART1转USB接口与上位机Jetson nano通过一路 USB串口通信。 还有4个直流电机接口分别与4个无刷电机相连接,控制电机的速度。电池通过 电源输入接口给STM32F40供电,再由电源输出接口给上位机供电。

激光雷达是一个集成了激光发射机、光接收器、旋转平台以及信息处理系统 的复杂系统,旨在利用激光束精确测量目标的位置、速度等特性。激光雷达与上 位机的数据传输是通过USAT串口通信协议实现的,如图4所示:

广角相机:采用广角相机作为本设计的智能采购机器人的相机,智能采购机器人通过广角相机获取外部环境的纹理和颜色等信息,然后通过 USB 与上位机通信,并且有相应的驱动程序或者支持的软件包,由于广角相机的视场角比较大,因此可以让智能采购机器人感知捕获更多更广泛的相机信息,如图5所示:

无刷减速电机是智能采购机器人的执行机构,其中具有霍尔编码器以实现精 确的轮速和里程监测。在无刷减速电机转动一圈时,减速比为30,并且编码器 能够产生9个脉冲信号,所以智能采购机器人的运动轮胎转动一圈会产生270 个脉冲信号。

选用的4个无刷电机分别由下位机STM32F407的4个直流电机接口相连接 控制智能采购机器人的运动,由下位机STM32F407输出PWM脉冲控制智能采 购机器人直行和转弯的速度,通过改变PWM方波的占空比调节速度的大小, PWM控制产生的波形如图所示:

电池是智能采购机器人的动力源,在整个控制系统中是非常重要的环节,为 机器人控制系统的各个模块提供能量,本设计的智能采购机器人所采用的电池电压为14.8V。

机器人整体结构展示 本设计搭建的智能采购机器人硬件实物图如图9所示,其硬件整体结构分为 3 层,其中最底层带有4个编码器无刷减速电机组成线性底盘,电机上装有麦克纳姆轮,上一层包括GPU嵌入式计算核心、MCU下位机计算核心、电池,最上层装有激光雷达和广角相机。

3.项目算法功能介绍:
系统主程序设计:(代码及详细解释)
#include <ros/ros.h>
#include <move_base_msgs/MoveBaseAction.h>
#include <actionlib/client/simple_action_client.h>
#include <geometry_msgs/PoseStamped.h>
#include <std_msgs/String.h>
#include <geometry_msgs/Twist.h>
#include <vector>
#include <unistd.h>typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;// 全局发布者声明
ros::Publisher light_response_pub;
ros::Publisher cmd_vel_pub;// 运动控制常量
const int MOVE_ITERATIONS_RIGHT = 14; // 向右平移的迭代次数
const int TARGET_INTERSECTION1 = 1;   // 路口1的目标索引
const int TARGET_INTERSECTION2 = 2;   // 路口2的目标索引
const int TARGET_INTERSECTION3 = 3;   // 路口3的目标索引// 运动控制函数
void moveRobot(ros::Publisher& cmd_vel_pub, double linear_x, double linear_y, double angular_z, int iterations, ros::Rate& rate) {geometry_msgs::Twist vel;vel.linear.x = linear_x;vel.linear.y = linear_y;vel.angular.z = angular_z;int count = 0;while (ros::ok() && count < iterations) {cmd_vel_pub.publish(vel);rate.sleep();count++;}
}// 发送目标点函数
bool sendNextGoal(MoveBaseClient& ac, int target_index) {std::vector<geometry_msgs::PoseStamped> goals(9);  // 注意修改为9个目标点for (auto& goal : goals) {goal.header.frame_id = "map";}//二维码识别位置goals[0].pose.position.x = 1.078;goals[0].pose.position.y = 0.578;goals[0].pose.orientation.z = 1.000;goals[0].pose.orientation.w = 0.006;//初入拣货区goals[1].pose.position.x = 0.522;goals[1].pose.position.y = 2.286;goals[1].pose.orientation.z = 0.668;goals[1].pose.orientation.w = 0.744;//拣货区找物品2号位goals[2].pose.position.x = 1.300;goals[2].pose.position.y = 2.300;goals[2].pose.orientation.z = 0.000;goals[2].pose.orientation.w = 1.000;//拣货区找物品3号位goals[3].pose.position.x = 0.406;goals[3].pose.position.y = 4.205;goals[3].pose.orientation.z = 0.717;goals[3].pose.orientation.w = 0.697;//红绿灯一号位goals[4].pose.position.x = 3.017;goals[4].pose.position.y = 4.045;goals[4].pose.orientation.z = 0.717;goals[4].pose.orientation.w = 0.697;//红绿灯二号位goals[5].pose.position.x = 3.947;goals[5].pose.position.y = 4.157;goals[5].pose.orientation.z = 0.723;goals[5].pose.orientation.w = 0.691;//巡线firstgoals[6].pose.position.x = 2.550;goals[6].pose.position.y = 3.291;goals[6].pose.orientation.z = -0.651;goals[6].pose.orientation.w = 0.759;//巡线secondgoals[7].pose.position.x = 4.502;goals[7].pose.position.y = 3.577;goals[7].pose.orientation.z = -0.737;goals[7].pose.orientation.w = 0.676;//仿真位置goals[8].pose.position.x = 1.012;goals[8].pose.position.y = 3.507;goals[8].pose.orientation.z = 0.000;goals[8].pose.orientation.w = 1.000;if (target_index < 0 || target_index >= goals.size()) {ROS_WARN("目标索引 %d 超出范围", target_index);return false;}move_base_msgs::MoveBaseGoal goal_msg;goal_msg.target_pose = goals[target_index];goal_msg.target_pose.header.stamp = ros::Time::now();ac.sendGoal(goal_msg);ac.waitForResult();if (ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) {ROS_INFO("发送目标点 %d 成功", target_index + 1);return true;} else {ROS_WARN("发送目标点 %d 失败", target_index + 1);return false;}
}// 处理红绿灯信号的回调函数
void lightSignalCallback(const std_msgs::String::ConstPtr& msg, MoveBaseClient& ac, ros::Publisher& cmd_vel_pub,ros::Publisher& pub) {std::string signal = msg->data;ROS_INFO("Received light signal: %s", signal.c_str());ros::Rate rate(10);if (signal == "102") {// 前往巡线firstROS_INFO("Received signal 102");sendNextGoal(ac, 6); // 发布消息first到 xunx 话题std_msgs::String msg;msg.data = "first";pub.publish(msg);ROS_INFO("Published to xunx: first");} else if (signal == "103") {// 前往红绿灯二号位ROS_INFO("Received signal 103");sendNextGoal(ac, 5);         // 通过 light_response_pub 发布响应信号std_msgs::String response_msg;response_msg.data = "114";light_response_pub.publish(response_msg);ROS_INFO("Published to light_response: 114");  moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 20, rate);                     sendNextGoal(ac, 7); // 发布消息second到 xunx 话题std_msgs::String msg;msg.data = "second";pub.publish(msg);ROS_INFO("Published to xunx: second");           }
}void yuyinCallback(const std_msgs::String::ConstPtr& msg, ros::Publisher& pub, MoveBaseClient& ac) {std::string yuny_string = msg->data;ROS_INFO("Received string: %s", yuny_string.c_str());ros::NodeHandle nh;ros::Publisher gengzong_pub = nh.advertise<std_msgs::String>("gengzong", 10);ros::Publisher light_start_pub = nh.advertise<std_msgs::String>("light_start", 10);ros::Publisher rece_start_pub = nh.advertise<std_msgs::String>("rece_start", 10);ros::Publisher simulate_start_pub = nh.advertise<std_msgs::String>("simulate_start", 10);ros::Publisher xz_sb_start_pub = nh.advertise<std_msgs::String>("xz_sb_start", 10);ros::Publisher xz_sb_end_pub = nh.advertise<std_msgs::String>("xz_sb_end", 10);ros::Subscriber rece_end_sub;ros::Subscriber simulate_end_sub;ros::Subscriber xz_sb_end_sub;ros::Subscriber bobao_end_sub;ros::Subscriber light_signal_sub;ros::Rate rate(10);ros::Rate wait_rate(10);ros::Rate wait_rate_bobao(10);  // 提前声明wait_rate_bobaostd_msgs::String simulate_start_msg;std_msgs::String light_start_msg;bool received_rece_end = false;bool received_xz_sb_end = false;bool received_simulate_end = false;bool received_light_signal = false;bool received_bobao_end = false;if (yuny_string == "qidong") {//到目标点0号点,二维码识别区sendNextGoal(ac, 0);// 发布消息99到 rece_start 话题std_msgs::String rece_start_msg;rece_start_msg.data = "99";rece_start_pub.publish(rece_start_msg);ROS_INFO("Published to rece_start: 99");// 等待接收 rece_end 话题的消息567bool received_rece_end = false;auto rece_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "567") {ROS_INFO("Received rece_end: 567");received_rece_end = true;}};rece_end_sub = nh.subscribe<std_msgs::String>("rece_end", 10, rece_end_callback);// 等待接收 rece_end 的消息567while (ros::ok() && !received_rece_end) {ros::spinOnce();wait_rate.sleep();}moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 30, rate);         //初入拣货区sendNextGoal(ac, 1);moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 10, rate);//然后让小车到中央白线框框内,仿真区域sendNextGoal(ac, 8);moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 10, rate);  // 发布消息99到 xz_sb_start 话题std_msgs::String xz_sb_start_msg;xz_sb_start_msg.data = "99";xz_sb_start_pub.publish(xz_sb_start_msg);ROS_INFO("Published to xz_sb_start: 99");// 等待接收 xz_sb_end 话题的消息bool received_xz_sb_end = false;auto xz_sb_end_callback = [&](const std_msgs::String::ConstPtr& msg) {if (msg->data == "88") {received_xz_sb_end = true;}};xz_sb_end_sub = nh.subscribe<std_msgs::String>("xz_sb_end", 10, xz_sb_end_callback); // 开始顺时针旋转360度geometry_msgs::Twist twist;twist.angular.z = -M_PI / 6; // 每秒30度ros::Time rotation_start_time = ros::Time::now();ros::Duration rotation_duration(26.0); // 旋转360度需要12秒bool rotation_completed = false;while (ros::ok() && !rotation_completed && ros::Time::now() - rotation_start_time < rotation_duration) {cmd_vel_pub.publish(twist);ros::spinOnce();if (received_xz_sb_end) {rotation_completed = true;}rate.sleep();}        // 停止旋转twist.angular.z = 0.0;cmd_vel_pub.publish(twist);        xz_sb_start_msg.data = "88";xz_sb_start_pub.publish(xz_sb_start_msg);ROS_INFO("Published to xz_sb_start: 88");if (!received_xz_sb_end) {//第一次如果没找到sendNextGoal(ac, 2);// 发布消息99到 xz_sb_start 话题std_msgs::String xz_sb_start_msg;xz_sb_start_msg.data = "99";xz_sb_start_pub.publish(xz_sb_start_msg);ROS_INFO("Published to xz_sb_start: 99");// 等待接收 xz_sb_end 话题的消息bool received_xz_sb_end = false;auto xz_sb_end_callback = [&](const std_msgs::String::ConstPtr& msg) {if (msg->data == "88") {received_xz_sb_end = true;}};xz_sb_end_sub = nh.subscribe<std_msgs::String>("xz_sb_end", 10, xz_sb_end_callback); // 开始顺时针旋转360度twist.angular.z = -M_PI / 6; // 每秒30度ros::Time rotation_start_time = ros::Time::now();ros::Duration rotation_duration(26.0); // 旋转360度需要12秒bool rotation_completed = false;while (ros::ok() && !rotation_completed && ros::Time::now() - rotation_start_time < rotation_duration) {cmd_vel_pub.publish(twist);ros::spinOnce();if (received_xz_sb_end) {rotation_completed = true;}rate.sleep();}        // 停止旋转twist.angular.z = 0.0;cmd_vel_pub.publish(twist);        xz_sb_start_msg.data = "88";xz_sb_start_pub.publish(xz_sb_start_msg);ROS_INFO("Published to xz_sb_start: 88");if (!received_xz_sb_end) {//第二次如果没找到//发布消息到 xz_sb_end话题std_msgs::String xz_sb_end_msg;xz_sb_end_msg.data = "force";xz_sb_end_pub.publish(xz_sb_end_msg);ROS_INFO("Published to xz_sb_end: force");sendNextGoal(ac, 8); //发布消息到 simulate_start话题std_msgs::String simulate_start_msg;simulate_start_msg.data = "start";simulate_start_pub.publish(simulate_start_msg);ROS_INFO("Published to simulate_start: start");// 等待接收 simulate_end 话题的消息10bool received_simulate_end = false;auto simulate_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "10") {ROS_INFO("Received simulate_end: 10");received_simulate_end = true;}};simulate_end_sub = nh.subscribe<std_msgs::String>("simulate_end", 10, simulate_end_callback);// 等待接收 simulate_end 的消息while (ros::ok() && !received_simulate_end) {ros::spinOnce();wait_rate.sleep();}sendNextGoal(ac, 4);moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 10, rate);        // 发布消息101到 light_start 话题std_msgs::String light_start_msg;light_start_msg.data = "101";light_start_pub.publish(light_start_msg);ROS_INFO("Published to light_start: 101");            // 订阅 light_signal 话题,等待102或103信号bool received_light_signal = false;auto light_signal_callback = [&](const std_msgs::String::ConstPtr& signal_msg) {lightSignalCallback(signal_msg, ac, cmd_vel_pub, pub);received_light_signal = true;};light_signal_sub = nh.subscribe<std_msgs::String>("light_signal", 10, light_signal_callback);            // 等待接收 light_signal 的消息while (ros::ok() && !received_light_signal) {ros::spinOnce();rate.sleep();}   bool received_bobao_end = false;auto bobao_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "89") {ROS_INFO("Received bobao_end: 89");received_bobao_end = true;}};bobao_end_sub = nh.subscribe<std_msgs::String>("bobao_end", 10, bobao_end_callback);// 等待接收 bobao_end 的消息while (ros::ok() && !received_bobao_end) {ros::spinOnce();wait_rate_bobao.sleep();} sendNextGoal(ac, 8);// 发布消息到 simulate_start 话题std_msgs::String simulate_start_msg;simulate_start_msg.data = "start";simulate_start_pub.publish(simulate_start_msg);ROS_INFO("Published to simulate_start: start");// 等待接收 simulate_end 话题的消息10bool received_simulate_end = false;auto simulate_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "10") {ROS_INFO("Received simulate_end: 10");received_simulate_end = true;}};simulate_end_sub = nh.subscribe<std_msgs::String>("simulate_end", 10, simulate_end_callback);// 等待接收 simulate_end 的消息while (ros::ok() && !received_simulate_end) {ros::spinOnce();wait_rate.sleep();}sendNextGoal(ac, 4);moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 10, rate);        // 发布消息101到 light_start 话题std_msgs::String light_start_msg;light_start_msg.data = "101";light_start_pub.publish(light_start_msg);ROS_INFO("Published to light_start: 101");// 订阅 light_signal 话题,等待102或103信号bool received_light_signal = false;auto light_signal_callback = [&](const std_msgs::String::ConstPtr& signal_msg) {lightSignalCallback(signal_msg, ac, cmd_vel_pub, pub);received_light_signal = true;};light_signal_sub = nh.subscribe<std_msgs::String>("light_signal", 10, light_signal_callback);// 等待接收 light_signal 的消息while (ros::ok() && !received_light_signal) {ros::spinOnce();rate.sleep();          }}}bool received_bobao_end = false;auto bobao_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "89") {ROS_INFO("Received bobao_end: 89");received_bobao_end = true;}};bobao_end_sub = nh.subscribe<std_msgs::String>("bobao_end", 10, bobao_end_callback);// 等待接收 bobao_end 的消息while (ros::ok() && !received_bobao_end) {ros::spinOnce();wait_rate_bobao.sleep();}sendNextGoal(ac, 8);// 发布消息到 simulate_start 话题std_msgs::String simulate_start_msg;simulate_start_msg.data = "start";simulate_start_pub.publish(simulate_start_msg);ROS_INFO("Published to simulate_start: start");// 等待接收 simulate_end 话题的消息10bool received_simulate_end = false;auto simulate_end_callback = [&](const std_msgs::String::ConstPtr& end_msg) {if (end_msg->data == "10") {ROS_INFO("Received simulate_end: 10");received_simulate_end = true;}};simulate_end_sub = nh.subscribe<std_msgs::String>("simulate_end", 10, simulate_end_callback);// 等待接收 simulate_end 的消息while (ros::ok() && !received_simulate_end) {ros::spinOnce();wait_rate.sleep();}sendNextGoal(ac, 4);moveRobot(cmd_vel_pub, 0.0, 0.0, 0.0, 10, rate);        // 发布消息101到 light_start 话题std_msgs::String light_start_msg;light_start_msg.data = "101";light_start_pub.publish(light_start_msg);ROS_INFO("Published to light_start: 101");// 订阅 light_signal 话题,等待102或103信号bool received_light_signal = false;auto light_signal_callback = [&](const std_msgs::String::ConstPtr& signal_msg) {lightSignalCallback(signal_msg, ac, cmd_vel_pub, pub);received_light_signal = true;};light_signal_sub = nh.subscribe<std_msgs::String>("light_signal", 10, light_signal_callback);// 等待接收 light_signal 的消息while (ros::ok() && !received_light_signal) {ros::spinOnce();rate.sleep();}       }
}int main(int argc, char **argv) {ros::init(argc, argv, "send_goals_node");ros::NodeHandle nh;// 初始化全局发布者light_response_pub = nh.advertise<std_msgs::String>("light_response", 10);cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 10);MoveBaseClient ac("move_base", true);while (!ac.waitForServer(ros::Duration(5.0))) {ROS_INFO("等待 move_base 行动服务器启动");}ros::Publisher pub = nh.advertise<std_msgs::String>("xunx", 10);ros::Subscriber yuyin_sub = nh.subscribe<std_msgs::String>("huanxing", 10,[&](const std_msgs::String::ConstPtr& msg) {yuyinCallback(msg, pub, ac);});ros::spin();return 0;
}
该系统由多个模块组成,设计由上位机与PC端进行远程连接完成人机互动, 用户在PC端给予智能采购机器人本次执行的采购任务和采购的目标地点,采购机器人可以自主规划路径前往目标地点,并且通过广角相机完成识别过程,从而完成采购任务,由于考虑到路面的复杂情况,还增加了采购机器人的智能避障功能和路标识别功能,在雷达采集到障碍物后,会重新规划路径完成避障功能;在摄像头识别到目标后,会根据路标完成下一步指示。主程序设计流程图如图所示:

场地信息采集子程序设计:
该子程序通过雷达设备实现场地环境信息的自动化采集,为后续路径规划提 供数据支持。程序运行流程如下:首先初始化雷达硬件,检测连接状态并配置扫 描参数(如分辨率、频率);随后启动雷达持续扫描,实时获取原始点云数据。 数据经预处理阶段完成滤波去噪与坐标系转换(通过ROS的TF库对齐全局坐 标),随后基于SLAM算法(如Gmapping)将多帧点云拼接并提取特征,生成 2D 栅格地图。程序循环检测场地覆盖率,若未完全覆盖则继续扫描,直至完整 地图构建完成后保存为通用格式(如PGM),并传输至上层模块。 场地信息采集子程序流程图如图所示:

路径规划子程序设计:
该子程序基于动态窗口算法(TEB)实现机器人路径规划功能。程序启动 后,首先接收目标点坐标信息并初始化算法参数(如最大速度、加速度约束等)。 规划过程中,实时获取机器人当前位置、速度及障碍物分布信息(基于ROS的地图数据)。借助动态速度窗口采样产生候选速度组合,模拟预判未来短时间 的运动轨迹,再结合避障、接近目标的情况和速度平滑性等多目标代价函数评估轨迹的得分,筛选出最理想的路径。若存在可通行的路径,于是输出线速度和角 速度控制指令驱动机器人运转;若没办法避障,就触发紧急停止或是重新进行规划,程序一直做循环,直至抵达目标点.。
货品拣选子程序设计:
该子程序基于YOLOv3目标检测算法实现货品识别与拣选功能。程序启动 后,首先初始化摄像头设备并加载预训练的YOLOv3模型(通过ROS的 darknet_ros 框架),实时捕获货架图像并进行多目标检测。识别结果(包括物品 类别、位置及置信度)通过ROS话题(如/darknet_ros/detections)发送至上位机。 上位机将检测到的物品与预设购物清单进行比对,若匹配成功则结束流程;若未 匹配则控制机器人移动至下一货架区域重新扫描,直至完成所有目标检索。系统 通过动态阈值过滤低置信度检测结果,确保识别准确性,同时支持多任务循环处 理,适应复杂购物场景需求。 货品拣选子程序设计流程图如图所示:

4.项目实施过程
系统终端通信配置:
在工作过程中,需要通过电脑的PC端来控制上下位机从而实现各种功能, 所以需要在开始调试之前完成电脑和智能机器人上位机的通信配置功能,从而可 以让智能采购机器人便于用户使用。 在虚拟机Ubuntu的主目录中打开一个终端。在本地电脑的终端输入ifconfig查看PC端IP地址。,本地电的终端中显示IP地址为 192.168.153.132,后续可以使用此IP的地址完成与机器人的通信。 打开本地电脑的终端查看IP地址后输入gedit.bashrc在最后面添加如下两行, 第一行为智能采购机器人上的IP,第二行为本地电脑上的IP,在本地电脑上打开终端,输入ssh-x ucar@后回 车,再输入智能采购机器人的密码ucar即可连接智能采购机器人地址,同时在文件夹中连接到服务器处输入sftp://ucar@ 后连接,连接成功后,安装相关开源的功能包即可完成串口通信、激光雷达、建图、 导航、广角相机、OpenCV等功能。
自主导航实现:
自主导航建图 打开终端,运行命令roslaunch ucar map ucar_mapping.launch ucar_mapping.launch 中包含了分布启动建图中的3个launch文件在终端输入rosrun teleop_twist_keyboard teleop_twist_keyboard.py,使用键盘控制智能采购机器人移动,从而完成建图操作,键盘控制快捷键,为了使机器人的建图效果更为理想化,建图的时候尽量避免智能采购机器人 自转、倒退、停止,使智能采购机器人运行的线路相对流畅
自主导航巡线实验场地搭建完成后如图所示:

运行命令roslaunch ucar_map ucar_mapping.launch 后在主机端打开 rviz,据 实际环境进行建图,在机器人终端运行命令rviz,在rviz界面左下角点击add, 添加Map,订阅/map话题,按下键盘相关指令来控制机器人的线性底盘,从而 实现机器人在实验场地内运行移动,不断调试直至在Rviz界面可以看到构建地 图的轮廓,即可看到建图效果通过 map_server 的 map_server 节点可以读取栅格地图数据,把此次建立的地图命名为map1111,在智能采购机器人端运行保存地图命令。 rosrun map_server map_saver-f ucar_ws/src/ucar_nav/maps/map1111,保存地 图的pgm和yaml文件到指定路径map1111.pgm 是一张图片,map1111.yaml 是一种文件,用于保存和描述创建 好的地图数据信息。 经过PS软件对构建的地图进行精细化处理。
场地信息采集子程序测试: 在终端输入roslaunchydlidar ydlidar.launch 启动雷达,开始数据采集,启动成功。
ucar_nav包基于包集navigation,修改ucar_nav包中的ucar_navigation.launch, 修改标注行,将地图路径改为已经建好的地图。这样就可以在ROS 运行的过程中调用所创建的地图。
启动rviz可视化界面后,在话题中添加/map话题加入地图和/scan话题加入 雷达后,会发现在原有的黑色地图周边会出现泛着红光和紫光的雷达信号线,红 光代表着对于反射回来的信号接收较为良好,紫光反之则代表较差,在机器人运 动的过程中,会根据雷达信号和地图信息来选择路径。
路径规划子程序测试: 在终端输入roslaunch ucar_controller base_driver.launch 启动线性底盘
智能采购机器人端打开新的终端,运行下面命令 roslaunch ucar_nav ucar_navigation.launch 在主机端打开rviz加载上节建好的地图,在rviz界面左下角点击add,添加 Map,订阅/map话题,全局代价地图和局部代价地图设置。
先设置好机器人线性底盘的初始位置和方向,然后再设定目标位置及方向, 机器人就可以实现导航效果。为了确保创建的地图和实际搭建的场景的方向基本 一致,使用鼠标旋转地图,然后在rviz中的使用“2DPoseEstimate”标定从而确 定好智能采购机器人底盘位于地图中的初始位置及智能采购机器人头的指向,通 过“2D Nav Goal”可以规划并且生成路径,控制智能采购机器人到达指定位置与 方向。
为了实现主函数控制机器人,通过反复分析测试,记录数据,选择以下目标 点作为本设计所需点位。 [INFO]:Position(1.407,-1.416, 0.000), Orientation(0.000, 0.000, 0.672, 0.740) = Angle: 1.475
[INFO]:Position(1.000,-0.824, 0.000), Orientation(0.000, 0.000, 1.000,-0.023) =Angle:-3.096
[INFO]:Position(0.066,-0.709, 0.000), Orientation(0.000, 0.000, 0.667, 0.745) = Angle: 1.459
[INFO]:Position(1.575,-0.244, 0.000), Orientation(0.000, 0.000, 0.737, 0.676) = Angle: 1.657
[INFO]:Position(0.288, 0.275, 0.000), Orientation(0.000, 0.000, 0.702, 0.712) = Angle: 1.557
[INFO]:Position(0.756, 1.815, 0.000), Orientation(0.000, 0.000, 0.645, 0.764) = Angle: 1.403
将6个目标点写入send_goals包中的send_goals_node.cpp 文件,打开一个终 端输入roslaunch ucar_nav ucar_navigation.launch ,机器人将依次到达设置的目标点。
自主导航参数调节: 调节参数是达成特定目标或提升系统性能的关键办法,若参数存在偏差,也 许会引起定位系统的性能下滑,让智能采购机器人在行驶过程里无法精准明确自 身的位置,这种定位存在误差的问题会进一步影响到里程计的准确性,引发里程计显示的行驶距离跟实际行驶距离产生偏差。里程计出现偏移,不仅会对智能采 购机器人导航精度有影响,还可能引起路线规划的失利,造成智能采购机器人无 法按照既定路线行驶。
为了加速智能采购机器人到达终点的速度,对自主导航巡线的以下几个参数 进行优化: (1)地图膨胀,由于智能采购机器人的大小是固定的,为了避免机器人在运行的过程中因为惯性与墙体发生碰撞,还需要考虑墙体与机器人之间的距离, 所以需要使用地图边缘膨胀功能。既要保证膨胀尺寸不能过小,与墙壁发生碰撞, 又不能过大导致机器人无法通过狭小的通道,需要保证和障碍物之间保留更大的 自由空间,通过修改地图的膨胀半径和障碍物系数可以实现功能。 (2)路径规划器,因为全局路径规划器仅是根据整体的地图与设置的起点 和终点的信息计算规划出一条路径,所以还需要局部路径规划器根据机器人的具 体物理属性来规划局部的运动姿态。这两者之间存在一定的偏差,如何赋权、设 置多大的偏差容限都是需要调整的重要参数。 (3)平滑路径,曲折的路径意味着更多的转弯和减速,使弯道平滑、让智 能采购机器人多走直线。为此引入梯度下降算法,避免直接使用网格格点规划路 径。进一步提升速度。同时设置更符合地图弯道半径的避障半径。在使用Rviz 建 立出地图之后,经过后期边缘处理使地图更加精确清晰,这可以减少地图的边缘 毛刺,让路径变得平滑。 (4)加速,在能够避免碰撞和正确行驶的前提下尽可能地快,增大加速度、 角加速度、速度上限和角速度上限。 (5)加速转弯,在过弯时观察到智能采购机器人速度过慢,规划器采用了 过于保守的速度以避免碰撞,因为增大了过弯的速度下限充分利用了智能采购机 器人的加速度实现顺滑的过弯。此外,使用了可视化调参工具rqt_reconfigure, 减少了繁琐的改代码调参过程。
麦克朗姆轮自转测试与实现: 机器人需要完成自转过程,通过ROS直接控制底盘可以完成此项功能调试过程中,按照代码逻辑需要12秒即可完成360度的旋转过程,但是由 于地面摩擦和电池电量等现实问题,无法满足要求,所以实际测试将自转运行时间改为13秒,效果良好。
5.项目数据分析
YOLOv3模型训练:
1 数据集标签的标定
在LabelImg 操作中,用户通过框选图像中的目标对象来生成训练 YOLO 所需的标准数据集。在本设计中,利用LabelImg对人工拍摄的数据 集进行标注。鉴于YOLOv3为目标检测算法,选择了LabelImg的YOLO 标注模式,并将标注结果保存为txt文件。在标注过程中,用户通过鼠标 拖动锚框来选定目标图像,确保每个目标都被完整的矩形框覆盖,同时最 小化框内非目标区域,以提高标注精度。选定后,用户还需为目标分配或 添加相应的类别标签,这是训练YOLO等目标检测算法的关键步骤。 具体操作为在图像中框选出目标对象,从而生成训练YOLO网络所需 的标准数据集
YOLO 标注模式下标注完成后数据集整体结构如图:

2 在Ubuntu 终端下载编译配置相关文件
要先下载再编译Darknet,此为一个开源的深度学习框架,YOLO作 为Darknet 标志性应用里的一个,作为一种高效且实时效果好的目标检测 算法。该独特的检测机制能在单次前向传播时快速识别图像中的多个对象, 还能精准输出这些对象的边界框及类别信息。为适配本设计所需要的环境 和需求,需要针对Darknet的配置文件Makefile 做对应修改,而后进行编 译流程,这一步是为了保证Darknet能在特定的软硬件环境里正常运转。
3 样本集构建
本设计主要针对苹果、香蕉、西瓜、可乐、蛋糕、土豆、彩椒、番茄、 牛奶、红绿灯等图片进行图像采集,根据采集需求通过ROS机器人的USB 相机拍摄图像,由模型所需样本为参照采集约1000张照片。根据本拍摄 到的图片进行筛选重建。本设计中的所有数据均按照YOLO格式进行了详 细的标注处理。为了确保模型训练与评估的准确性和有效性,将数据集的 80%部分划定为训练集,专门用于模型的训练与优化;而剩余的20%部分 则设定为测试集,旨在检验训练后模型的性能和泛化能力。 将所有需要用到的数据都放于darknet的JPGImages 的目录下方便在 后续训练过程中调用。
4 训练数据集
在开展深度学习模型训练工作起始阶段,一开始的主要步骤是获取预 先训练好的权重文件,也就是yolov3-tiny相关的 v.15,yolov3-tiny 是一 种针对物体识别任务预训练好的权重模型。值得警觉的是,yolov3-tiny作 为YOLOv3 模型的轻量级变体,经由缩减卷积层数量以及参数量,实现了 速度的显著增进,尽管这样也许会牺牲掉一些精确度,借助这个权重模型, 可以对图像及视频素材中的多种目标实施探测,并输出包含目标类别、空 间位置、可信度等关键信息的探测结果。就每一个已识别的目标而言,模 型会生成一个矩形边界框来精准定位目标物体,并顺带标识其所属的类别。 关键参数配置 (1)网络配置文件 输入分辨率:width=416, height=416(平衡检测精度与计算速度) 锚框(Anchors):根据数据集重新聚类生成。 anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 类别数:classes=11(修改 3 个 YOLO 层的 classes 参数) 卷积核数:每个 YOLO 层前最后一个卷积层的 filters=(classes + 5)*3 → filters=48 (2)训练参数 基础学习率:learning_rate=0.001 批次与子批次:batch=64, subdivisions=16 训练轮次:max_batches=10000 数据增强:启用flip=1, blur=1, jitter=0.3 为使模型能充分挖掘数据集特性以实现充分学习,科学设定迭代次数 意义重大,选定好的迭代轮数为8000次,这一数量级偏大,目的是借助 频繁遍历训练数据集,不停修正模型参数。伴随训练进程的逐步深入, Darknet 框架将采取系统措施调整模型权重,让它渐进地适应数据集的特 有模式及分布,一旦做完预定的8000轮训练,将自动生成一个把所有优 化参数作为训练成果汇总的全新权重文件。此文件作为模型学习知识的载 体,对于后续的性能评估、测试环节及实际部署均具有保存价值。
5 将权重文件导入机器人系统 首先,将先前训练得到的权重文件yolov3-tiny_final_weights 以及与其 配套的配置文件yolov3-tiny_cfg 转移到机器人系统的指定目录下。第一步 需要在机器人系统中新建文件,并命名为yolov3-tiny.yaml,在该文件中, 需要详细写入与模型相关的配置信息,包括权重文件的名称、cfg配置文 件的名称、图像类别的全部名称等。完成yaml文件的编写后,第二步进 行编译,以确保权重文件能够被机器人系统正确配置和使用。
6 launch 文件编写 编写launch 文件将摄像头图像采集的节点与图像识别的节点进行逻辑上的 连接和配置。将摄像头节点和识别节点的功能包名、节点类型、节点名称等按功 能运行顺序进行编写,当保存后只需通过终端命令行打开这个launch文件,系 统就会自动启动摄像头节点和识别节点,并开始实时的图像捕获和识别过程。[15] 通过这种方式,可以方便地实现摄像头与识别节点的集成。 通过在Ubuntu 终端运行指令roslaunchdarknet_ros darknet_ros.launch,可以 得到实时画面。
货品拣选子程序测试: 首先对训练过的图片进行测试。在darknet文件夹下打开终端,输入 指令,通过检测观察图像识别情况。通过输入指令来检验训练集中的图片 检测准确性。
./darknet detector test cfg/voc.data cfg/yolov3-tiny.cfg backup/yolov3-tiny_final. weights data/banana.png
./darknet detector test cfg/voc.data cfg/yolov3-tiny.cfg backup/yolov3-tiny_final. weights data/coke.png

实时图像识别测试前首先需要将摄像头采集的信号画面显示到显示 屏上,通过显示屏就可以直观的看到摄像头识别的情况。通过在终端输入 以下指令实现实时检测。 roslaunch darknet_ros darknet_ros.launch 开启后:

整体测试: 打开2个终端,分别输入以下2条命令。 roslaunch ucar_nav ucar_navigation.launch 打开自主导航。 roslaunch darknet_ros darknet_ros.launch 打开摄像头识别。 在进行自主导航时,小车会根据所发送的目标点位进行路径规划,并且在到 达相应点位后会在上位机中显示。
到达目的地后,控制底盘开始进行自转,在自转的过程中,对图像进行识别。

在进行视觉识别的过程中,当摄像头调用完YOLO模型识别到物品后,会 将物品的类别发送到/darknet_ros/bounding_boxes 这个话题中,通过在上位机中 订阅话题,就可以完成对于物品类别的识别。
6.不足之处
(1)定位不准确,在跑的过程中会出现里程计偏移导致路线规划失败。后 续可能会加入多传感器融合,选择精度更高、性能更稳定的传感器,使用激光雷 达与 IMU 的信息融合,完成激光雷达惯性里程计定位系统构建可以实现机器人 精确位姿估计,作为环境感知的前提保障。 (我们的车IMU是坏的就没用,哈哈)
(2)视觉识别的过程中,光线和角度对于识别的结果任然存在一定的影响,为了适应更加普遍的场景,后续可能会考虑使用更加先进的YOLO的算法或者采取更多的样本作为数据集。
(注:本文来自一位20届智能车竞赛创意组国二学弟的投稿,希望对大家能有帮助)
