Gazebo环境下基于ROS和激光雷达的阿克曼小车避障(2025版)
本实验通过对图片处理,使得阿克曼底盘车沿着车道线自动行驶。同时根据激光雷达数据对周围进行判断来规避障碍物。
实验室资源方式简介
进入实操前,请确保阿里云账号满足以下条件:
个人账号资源
使用您个人的云资源进行操作,资源归属于个人。
平台仅提供手册参考,不会对资源做任何操作。
确保已完成云工开物300元代金券领取。
已通过实名认证且账户余额≥100元。
本次实验将在您的账号下开通实操所需计算型实例规格族c7a,费用约为:25元(以实验时长2小时预估,具体金额取决于实验完成的时间),需要您通过阿里云云工开物学生专属300元抵扣金兑换本次实操的云资源。
如果您调整了资源规格、使用时长,或执行了本方案以外的操作,可能导致费用发生变化,请以控制台显示的实际价格和最终账单为准。
领取专属权益及创建实验资源
在开始实验之前,请先点击右侧屏幕的“进入实操”再进行后续操作

领取300元高校专属权益优惠券(若已领取请跳过)
实验产生的费用优先使用优惠券,优惠券使用完毕后需您自行承担。

实验步骤
1、服务部署
点击链接,进入部署页面
按弹窗提示进行权限申请。其中【姓名】、【电话】、【邮箱】为必填项,完成填写后点击【确定】
说明请填写您的学校邮箱(.edu),便于审核

提交申请后将提示

当申请通过后,将会收到短信提示可以进行部署

刷新部署页面,按下图设置【服务实例名称】、【地域】、【实例密码】
服务实例名称:test(可自定义命名)
地域:华东2(上海)
实例密码:Sjtu@520
说明输入实例密码时请注意大小写,请记住您设置的实例名称及对应密码,后续实验过程会用到。

完成填写后点击【下一步:确认订单】

核对实例信息及价格预览,无误请点击【立即创建】
重要领取300元优惠券后,资源应为0元/小时,且会提示【您当前账户的余额充足】!若提示余额不足等,请检查是否正确领取优惠券
创建成功,点击【去列表查看】

查看实例,点击左侧的图标展开目录

选择目录中的【云服务器ECS】

云服务器ECS—实例—远程连接

下拉展开更多登录方式,选择【通过VNC远程连接】

输入实例密码:Sjtu@520(请输入您设置的密码)后回车

点击左侧第3个图标,点击aliyun_ws文件夹

进入aliyun_ws文件夹后,在空白处点击鼠标右键,选择Open in Terminal


2、代码部分
程序使用的是raceworld_1car_laser场景,由raceworld_1car_laser.launch文件启动。找到aliyun_ws/src/raceworld/launch文件夹中的raceworld_1car_laser.launch文件并打开。
在launch文件内加载了多个控制器,其中left_rear_wheel_velocity_controller, right_rear_wheel_velocity_controller,left_front_wheel_velocity_controller,right_front_wheel_velocity_controller,left_steering_hinge_position_controller和right_steering_hinge_position_controller接收ROS消息,分别控制了左右后轮速度,左右前轮速度和转向角度。
<node name="controller_manager" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="left_rear_wheel_velocity_controller right_rear_wheel_velocity_controller left_front_wheel_velocity_controller right_front_wheel_velocity_controller left_steering_hinge_position_controller right_steering_hinge_position_controller joint_state_controller"/>在加载控制器代码的下面,加载了一个名为servo_comannds.py的代码文件。
<node pkg="raceworld" type="servo_commands.py" name="servo_commands" output="screen" >打开aliyun_ws/src/raceworld/src文件夹中的servo_comannds.py文件我们可以看到,代码中新建了一个名为servo_comannds的节点,他订阅并接收/car1/ackermann_cmd_mux/output消息。
robot_name = "car" def servo_commands(): rospy.init_node('servo_commands', anonymous=True) robot_name = rospy.get_param('~robot_name') rospy.Subscriber("ackermann_cmd_mux/output", AckermannDriveStamped, set_throttle_steer) # spin() simply keeps python from exiting until this node is stopped rospy.spin() if __name__ == '__main__': try: servo_commands() except rospy.ROSInterruptException: pass在接收到消息后,经过适当的转换,将速度和转向信息发布给之前所述六个控制器。
def set_throttle_steer(data): pub_vel_left_rear_wheel = rospy.Publisher("left_rear_wheel_velocity_controller/command", Float64, queue_size=1) pub_vel_right_rear_wheel = rospy.Publisher("right_rear_wheel_velocity_controller/command", Float64, queue_size=1) pub_vel_left_front_wheel = rospy.Publisher("left_front_wheel_velocity_controller/command", Float64, queue_size=1) pub_vel_right_front_wheel = rospy.Publisher("right_front_wheel_velocity_controller/command", Float64, queue_size=1) pub_pos_left_steering_hinge = rospy.Publisher("left_steering_hinge_position_controller/command", Float64, queue_size=1) pub_pos_right_steering_hinge = rospy.Publisher("right_steering_hinge_position_controller/command", Float64, queue_size=1) throttle = data.drive.speed*28 steer = data.drive.steering_angle pub_vel_left_rear_wheel.publish(throttle) pub_vel_right_rear_wheel.publish(throttle) pub_vel_left_front_wheel.publish(throttle) pub_vel_right_front_wheel.publish(throttle) pub_pos_left_steering_hinge.publish(steer) pub_pos_right_steering_hinge.publish(steer)在launch文件中,还加载了一个名为control_servo.py的文件。
<nodepkg="raceworld" type="control_servo.py" name="control_servo" output="screen"/>打开该文件,可以看到新建了一个名为control_servo的节点,并订阅了Twist类型的cmd_akm1消息。
def cmd_to_akm(): global pub rospy.init_node('control_servo', anonymous=True) pub = rospy.Publisher("/car1/ackermann_cmd_mux/output", AckermannDriveStamped, queue_size=10) rospy.Subscriber("cmd_akm1", Twist, callback) rospy.spin() pass if __name__ =='__main__': cmd_to_akm() pass当接收到订阅的消息后,新建/car1/ackermann_cmd_mux/output主题的发布者,并将AckermannDriveStamped类型的消息数据设置为合适的值后发布出去。
def callback(msg): global pub akm = AckermannDriveStamped() if msg.linear.x != 0: akm.drive.speed = msg.linear.x*1.80 akm.drive.steering_angle = atan((msg.angular.z/msg.linear.x)*0.133) else: akm.drive.speed = 0 akm.drive.steering_angle = 0 pub.publish(akm) pass雷达避障程序由aliyun_ws/src/raceworld/src下的laser_scan.py实现。
在主函数中分别创建摄像头和激光雷达消息的订阅者。
if __name__ == '__main__': rospy.init_node('listener', anonymous=True) cmd_vel_pub = rospy.Publisher('cmd_akm1', Twist, queue_size=10) rospy.Subscriber("scan", sensor_msgs.msg.LaserScan , LaserScanProcess) rospy.Subscriber("/car1/camera/zed_left/image_rect_color_left", Image, image_callback) rate = rospy.Rate(10) #10hz rospy.spin() pass订阅的摄像头消息回调函数负责小车的正常巡线行驶。
def image_callback(msg): bridge = cv_bridge.CvBridge() frame = bridge.imgmsg_to_cv2(msg, 'bgr8') follow_line(frame, "yellow") pass def set_roi_forward(h, w, mask): search_top = int(3 * h / 4) search_bot = search_top + 20 #感兴趣区域外全部改为黑色 mask[0:search_top, 0:w] = 0 mask[search_bot:h, 0:w] = 0 return mask pass def follow_line(image, color): cmd_vel_pub = rospy.Publisher("cmd_akm1", Twist, queue_size=10) #转换为HSV图像 hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) #cv2.namedWindow("hsv image",0) #cv2.imshow("hsv image",hsv) lower_yellow = np.array([26, 43, 46]) upper_yellow = np.array([34, 255, 255]) #转换为二值图,黄色范围内的车道线为白色,其他范围为黑色 mask = cv2.inRange(hsv, lower_yellow, upper_yellow) #cv2.namedWindow("binary image",0) #cv2.imshow("binary image",mask) h, w = mask.shape #print(mask.shape) #设置感兴趣区域ROI mask = set_roi_forward(h, w, mask) #cv2.namedWindow("region of interest",0) #cv2.imshow("region of interest",mask) #获得图像矩 M = cv2.moments(mask) if M['m00'] > 0: cx = int(M['m10'] / M['m00'])-235 cy = int(M['m01'] / M['m00']) # print(cx, cy) #在质心画圆 cv2.circle(image, (cx, cy), 20, (0, 0, 255), -1) if flag: err = cx - w / 2 - 50 twist = Twist() twist.linear.x = 0.08 twist.angular.z = -float(err / 2.0) / 50 cmd_vel_pub.publish(twist) else: rospy.sleep(4.278) cv2.namedWindow("camera",0) cv2.imshow("camera", image) cv2.waitKey(1) pass订阅的激光雷达消息数据被处理后,数据中的ranges被转换为numpy数组,然后通过阈值过滤,找出大于THRESHOLD(1.5米)的距离。然后,通过groupby函数找到最大的连续区域(即最大的间隙),并计算这个间隙的最小和最大角度,得到平均间隙角度turn_angle。根据不同的角度范围,设置不同的线速度和角速度,从而让机器人转向避开障碍物。如果间隙太小(average_gap <35),则停止并关闭节点。此外,当转向角度在特定范围内时,调整flag的值,控制是否进行视觉巡线。
turn_angle = 90 THRESHOLD = 1.5 #THRESHOLD value for laser scan. PI = 3.14 Kp1 = 0.047 Kp2 = 0.0325 Kp3 = 2 flag = True def check_gap(i_x): i,x = i_x return i-x def LaserScanProcess(data): range_angels = np.arange(len(data.ranges)) ranges = np.array(data.ranges) range_mask = (ranges > THRESHOLD) ranges = list(range_angels[range_mask]) # print(ranges) gap_list = [] for k, g in groupby(enumerate(ranges), check_gap): #gap_list.append(map(itemgetter(1), g)) gap_list.append(list(map(itemgetter(1), g))) gap_list.sort(key=len) largest_gap = gap_list[-1] min_angle, max_angle = largest_gap[0]*((data.angle_increment)*180/PI), largest_gap[-1]*((data.angle_increment)*180/PI) average_gap = (max_angle - min_angle) / 2 global flag global turn_angle turn_angle = min_angle + average_gap if average_gap < 35: stop(1) print(average_gap) print("stop now!") time.sleep(3) rospy.signal_shutdown("~~~") elif turn_angle < 40 or turn_angle > 140: flag = False LINX = 0.028 angz = Kp1 * (-1) * (90 - turn_angle) print("前方检测到障碍物") command = Twist() print(angz,turn_angle) print("正在避让\n") command.linear.x = LINX command.angular.z = angz cmd_vel_pub.publish(command) elif (turn_angle < 48 and turn_angle > 40) or (turn_angle > 132 and turn_angle < 140): flag = False LINX = 0.038 angz = Kp2 * (-1) * (90 - turn_angle) print("侧前方检测到障碍物") command = Twist() print(angz,turn_angle) print("正在避让\n") command.linear.x = LINX command.angular.z = angz cmd_vel_pub.publish(command) elif (turn_angle < 50 and turn_angle > 48) or (turn_angle > 130 and turn_angle < 132): flag = False LINX = 0.087 angz = Kp3 / (90 - turn_angle) print("侧面检测到障碍物") command = Twist() print(angz,turn_angle) print("正在避让\n") command.linear.x = LINX command.angular.z = angz cmd_vel_pub.publish(command) else: flag = True passdef stop(id): index = id cmd_vel_pub = rospy.Publisher("cmd_akm"+str(index), Twist, queue_size=10) twist = Twist() twist.linear.x = 0.0 twist.angular.z = 0.0 for i in range(20): cmd_vel_pub.publish(twist) time.sleep(2)3、实验操作
在aliyun_ws路径下新建终端,输入命令开启raceworld_1car_laser Gazebo场景。
source devel/setup.bash roslaunch raceworld raceworld_1car_laser.launch场景中小车会显示激光雷达扫描区域,以及在道路上生成障碍物。

在aliyun_ws路径下新建终端,输入命令开启程序。
source devel/setup.bash rosrun raceworld laser_scan.py小车在巡线过程中遇到障碍物时,会在终端显示,并且做出拐弯避障绕开障碍物的行为。

清理资源
在云服务器ECS界面选择实例——全部操作——实例状态——释放

选择立即释放。

确认选项。

进行安全验证后成功释放实例。

场景简介
本实验通过对图片处理,使得阿克曼底盘车沿着车道线自动行驶。同时根据激光雷达数据对周围进行判断来规避障碍物。
背景知识
学生需要有一定的C++ 基础或者Python基础来完成此实验。
关闭实验
在完成实验后,点击 结束实操

点击 取消 回到实验页面,点击 确定 跳转实验评分

请为本次实验评分,并给出您的建议,点击 确认,结束本次实验





















