#!/usr/bin/env python
# coding=utf-8
import rospy
import actionlib
import os
import threading
import time
import numpy as np
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import Image
from geometry_msgs.msg import PoseStamped, Twist
from my_control.msg import simulation
from std_msgs.msg import String, Bool
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from actionlib_msgs.msg import GoalStatus
from pyzbar import pyzbar
import cv2
from playsound import playsound
from darknet_ros_msgs.msg import BoundingBoxes, BoundingBox
class AutomationNode:
# 状态定义
STATE_IDLE = "IDLE" # 空闲状态
STATE_NAVIGATING = "NAVIGATING" # 导航状态
STATE_ARRIVED = "ARRIVED" # 抵达目标点
STATE_SCANNING = "SCANNING" # 搜索二维码
STATE_PLAYING = "PLAYING" # 播放音频
STATE_SEARCHING = "SEARCHING" # 搜索目标物品
STATE_FOUND_TARGET = "FOUND_TARGET" # 找到目标物品
STATE_WAITING_FOR_TASK3 = "WAITING_FOR_TASK3" # 等待任务3指令
STATE_TRAFFIC_LIGHT_DETECTION = "TRAFFIC_LIGHT_DETECTION" # 交通灯识别状态
STATE_TASK3_NAVIGATING = "TASK3_NAVIGATING" # 任务3导航状态
def __init__(self):
rospy.init_node('automation_node', anonymous=True)
# 状态变量
self.current_state = self.STATE_IDLE
self.target_waypoint = None
self.qr_detected = False
self.waypoint_index = 0
self.task3_started = False # 任务3是否已启动
# ROS通信设置
self.bridge = CvBridge()
self.speech_sub = rospy.Subscriber('/mic/recognise_result', String, self.speech_callback)
self.arrival_sub = rospy.Subscriber('/arrival_status', Bool, self.arrival_callback)
self.image_sub = None
self.status_pub = rospy.Publisher('/task_status', String, queue_size=10)
self.qr_result_pub = rospy.Publisher('/qrcode_result', String, queue_size=10)
self.cmd_vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
self.yolo_sub = rospy.Subscriber('/darknet_ros/bounding_boxes', BoundingBoxes, self.yolo_callback)
# 二维码参数配置
self.display = rospy.get_param('~display', False)
self.min_size = rospy.get_param('~min_size', 100)
self.process_counter = 0
self.process_every_n = 5
# MoveBase动作客户端 - 等待服务器启动
self.move_base_client = actionlib.SimpleActionClient('move_base', MoveBaseAction)
rospy.loginfo("等待move_base服务器...")
self.move_base_client.wait_for_server() # 无限期等待直到服务器可用
rospy.loginfo("move_base服务器已连接")
# 预定义航点(根据实际环境配置)
self.waypoints = [
# 任务1相关航点
self.create_pose(0.86228, 0.643816, 0.0, 0.0, 0.0, 0.999994, -0.00352223), # 点1: 扫描点,识别二维码
self.create_pose(0.239635, 2.22449, 0.0, 0.0, 0.0, 0.625221, 0.780448), # 点2: 到达任务1的出口
# 任务2搜索航点
self.create_pose(1.63196, 2.63176, 0.0, 0.0, 0.0, -0.350634, 0.936513), # 点3: 搜索点1
self.create_pose(1.353, 4.08081, 0.0, 0.0, 0.0, 0.35119, 0.936304), # 点4: 搜索点2
self.create_pose(0.445499, 3.68565, 0.0, 0.0, 0.0, 0.900844, 0.434142), # 点5: 搜索点3
# 任务2终点
self.create_pose(1.1181, 3.55528, 0.0, 0.0, 0.0, 0.0148318, 0.99989), # 点6: 任务2的终点
# 任务3相关航点
self.create_pose(2.28661, 4.04943, 0.0, 0.0, 0.0, 0.0, 1), # 点7: 门
self.create_pose(2.69836, 3.77956, 0.0, 0.0, 0.0, 0.745125, 0.666924), # 点8: 路灯1
self.create_pose(2.56047, 3.24088, 0.0, 0.0, 0.0, -0.60105, 0.799212), # 点9: 路口1
self.create_pose(4.36605, 2.0, 0.0, 0.0, 0.0, 0.0, 1.0), # 点10: 路灯2
self.create_pose(3.0, 3.90711, 0.0, 0.0, 0.0, 0.698666, 0.715448) # 点11: 路口2
]
# 航点索引常量(提高可读性)
self.WAYPOINT_SCAN = 0
self.WAYPOINT_TASK1_EXIT = 1
self.WAYPOINT_SEARCH1 = 2
self.WAYPOINT_SEARCH2 = 3
self.WAYPOINT_SEARCH3 = 4
self.WAYPOINT_TASK2_END = 5
self.WAYPOINT_DOOR = 6
self.WAYPOINT_LIGHT1 = 7
self.WAYPOINT_CROSS1 = 8
self.WAYPOINT_LIGHT2 = 9
self.WAYPOINT_CROSS2 = 10
# 音频文件映射
self.audio_files = {
"Fruit": "/home/ucar/ucar_ws/src/mp3/Fruit.mp3",
"Vegetable": "/home/ucar/ucar_ws/src/mp3/Vegetable.mp3",
"Dessert": "/home/ucar/ucar_ws/src/mp3/Dessert.mp3",
"apple": "/home/ucar/ucar_ws/src/mp3/apple.mp3",
"watermelon": "/home/ucar/ucar_ws/src/mp3/watermelon.mp3",
"banana": "/home/ucar/ucar_ws/src/mp3/banana.mp3",
"potato": "/home/ucar/ucar_ws/src/mp3/potato.mp3",
"tomato": "/home/ucar/ucar_ws/src/mp3/tomato.mp3",
"chili": "/home/ucar/ucar_ws/src/mp3/chili.mp3",
"cake": "/home/ucar/ucar_ws/src/mp3/cake.mp3",
"coco": "/home/ucar/ucar_ws/src/mp3/coco.mp3",
"milk": "/home/ucar/ucar_ws/src/mp3/milk.mp3",
"load_1": "/home/ucar/ucar_ws/src/mp3/load_1.mp3",
"load_2": "/home/ucar/ucar_ws/src/mp3/load_2.mp3"
}
# 目标搜索相关变量
self.qr_result = 0
self.target_object = None
self.search_timeout = 15.0 # 每个搜索点的超时时间(秒)
self.search_start_time = None
self.search_timer = None
# 目标类别映射
self.test1_categories = {
1: ['apple', 'watermelon', 'banana'],
2: ['potato', 'tomato', 'chili'],
3: ['cake', 'coco', 'milk']
}
# 任务3相关变量
self.traffic_light_detected = False
self.traffic_light_result = None # 'red' 或 'green'
rospy.loginfo("自动化节点已启动,等待语音指令...")
rospy.on_shutdown(self.shutdown)
def create_pose(self, x, y, z, qx, qy, qz, qw):
"""创建导航目标位姿"""
pose = PoseStamped()
pose.header.frame_id = "map"
pose.header.stamp = rospy.Time.now()
pose.pose.position.x = x
pose.pose.position.y = y
pose.pose.position.z = z
pose.pose.orientation.x = qx
pose.pose.orientation.y = qy
pose.pose.orientation.z = qz
pose.pose.orientation.w = qw
return pose
def navigate_to_waypoint(self, waypoint_index):
"""导航到指定航点"""
if waypoint_index >= len(self.waypoints):
rospy.logwarn("无效的航点索引: %d", waypoint_index)
return
self.waypoint_index = waypoint_index
waypoint = self.waypoints[waypoint_index]
rospy.loginfo("导航到航点 %d", waypoint_index + 1)
# 根据任务设置状态
if self.task3_started:
self.current_state = self.STATE_TASK3_NAVIGATING
else:
self.current_state = self.STATE_NAVIGATING
self.status_pub.publish("NAVIGATING_TO_TARGET")
# 使用move_base动作客户端发送目标
goal = MoveBaseGoal()
goal.target_pose = waypoint
self.move_base_client.send_goal(goal)
# 设置定时器检查导航状态
rospy.Timer(rospy.Duration(1), self.check_navigation_status, oneshot=False)
def check_navigation_status(self, event):
"""检查导航状态(使用move_base动作)"""
state = self.move_base_client.get_state()
if state == GoalStatus.SUCCEEDED:
rospy.loginfo("成功到达航点 %d", self.waypoint_index + 1)
self.handle_arrival()
# 停止定时器
event.new_message = None # 停止定时器
elif state in [GoalStatus.ABORTED, GoalStatus.PREEMPTED]:
rospy.logwarn("导航失败,尝试重新规划...")
self.navigate_to_waypoint(self.waypoint_index)
# 停止当前定时器
event.new_message = None
def handle_arrival(self):
"""处理到达航点后的逻辑"""
self.current_state = self.STATE_ARRIVED
self.status_pub.publish("ARRIVED_AT_TARGET")
# 发布到达状态
arrival_pub = rospy.Publisher('/arrival_status', Bool, queue_size=10)
arrival_pub.publish(True)
def speech_callback(self, msg):
"""处理语音识别结果"""
rospy.loginfo(f"收到语音指令: {msg.data}")
# 处理初始指令
if "ok" in msg.data.lower() and self.current_state == self.STATE_IDLE:
rospy.loginfo("收到语音指令,开始导航到航点1")
self.navigate_to_waypoint(self.WAYPOINT_SCAN)
# 处理任务3启动指令
elif "start task3" in msg.data.lower() and self.current_state == self.STATE_WAITING_FOR_TASK3:
rospy.loginfo("收到任务3启动指令,开始导航到门(点7)")
self.task3_started = True
self.navigate_to_waypoint(self.WAYPOINT_DOOR)
def arrival_callback(self, msg):
"""处理到达状态"""
if not msg.data or self.current_state != self.STATE_ARRIVED:
return
rospy.loginfo(f"处理航点 {self.waypoint_index+1} 的到达逻辑")
# 任务1: 二维码扫描点
if self.waypoint_index == self.WAYPOINT_SCAN:
rospy.loginfo("启动二维码识别...")
self.current_state = self.STATE_SCANNING
self.status_pub.publish("SCANNING")
self.image_sub = rospy.Subscriber('/usb_cam/image_raw', Image, self.image_callback)
# 任务1出口
elif self.waypoint_index == self.WAYPOINT_TASK1_EXIT:
rospy.loginfo("到达任务1出口,开始任务2")
self.start_searching()
# 任务2搜索点
elif self.waypoint_index in [self.WAYPOINT_SEARCH1, self.WAYPOINT_SEARCH2, self.WAYPOINT_SEARCH3]:
rospy.loginfo(f"在航点 {self.waypoint_index+1} 开始搜索目标...")
self.start_searching()
# 任务2终点
elif self.waypoint_index == self.WAYPOINT_TASK2_END:
rospy.loginfo("到达任务2终点,等待任务3指令...")
self.current_state = self.STATE_WAITING_FOR_TASK3
self.status_pub.publish("WAITING_FOR_TASK3")
# 任务3: 门
elif self.waypoint_index == self.WAYPOINT_DOOR:
rospy.loginfo("到达门,前往路灯1(点8)")
self.navigate_to_waypoint(self.WAYPOINT_LIGHT1)
# 任务3: 路灯1
elif self.waypoint_index == self.WAYPOINT_LIGHT1:
rospy.loginfo("到达路灯1,开始识别交通灯...")
self.current_state = self.STATE_TRAFFIC_LIGHT_DETECTION
self.status_pub.publish("DETECTING_TRAFFIC_LIGHT")
self.traffic_light_detected = False
self.traffic_light_result = None
# 设置超时定时器
if self.search_timer:
self.search_timer.shutdown()
self.search_timer = rospy.Timer(rospy.Duration(self.search_timeout),
self.handle_traffic_light_timeout,
oneshot=True)
# 订阅图像用于目标检测
if not self.image_sub:
self.image_sub = rospy.Subscriber('/usb_cam/image_raw', Image, self.yolo_image_callback)
# 任务3: 路灯2
elif self.waypoint_index == self.WAYPOINT_LIGHT2:
rospy.loginfo("到达路灯2,开始识别交通灯...")
self.current_state = self.STATE_TRAFFIC_LIGHT_DETECTION
self.status_pub.publish("DETECTING_TRAFFIC_LIGHT")
self.traffic_light_detected = False
self.traffic_light_result = None
# 设置超时定时器
if self.search_timer:
self.search_timer.shutdown()
self.search_timer = rospy.Timer(rospy.Duration(self.search_timeout),
self.handle_traffic_light_timeout,
oneshot=True)
# 任务3: 路口1或路口2
elif self.waypoint_index in [self.WAYPOINT_CROSS1, self.WAYPOINT_CROSS2]:
rospy.loginfo(f"到达路口{self.waypoint_index-7},准备进行下一步任务...")
self.status_pub.publish("TASK3_COMPLETED")
self.current_state = self.STATE_IDLE
self.task3_started = False
# 根据到达的路口播放不同的音频
if self.waypoint_index == self.WAYPOINT_CROSS1:
rospy.loginfo("在路口1播放load_1音频")
audio_file = self.audio_files.get("load_1")
else:
rospy.loginfo("在路口2播放load_2音频")
audio_file = self.audio_files.get("load_2")
if audio_file and os.path.exists(audio_file):
threading.Thread(target=self.play_audio_thread, args=(audio_file,)).start()
rospy.loginfo("任务3完成,等待新指令...")
def start_searching(self):
"""启动目标搜索"""
rospy.loginfo("开始搜索目标...")
self.current_state = self.STATE_SEARCHING
self.status_pub.publish("SEARCHING_TARGET")
self.search_start_time = rospy.Time.now()
# 设置超时定时器
if self.search_timer:
self.search_timer.shutdown()
self.search_timer = rospy.Timer(rospy.Duration(self.search_timeout),
self.handle_search_timeout,
oneshot=True)
# 订阅图像用于目标检测
if not self.image_sub:
self.image_sub = rospy.Subscriber('/usb_cam/image_raw', Image, self.yolo_image_callback)
def handle_search_timeout(self, event):
"""处理搜索超时"""
if self.current_state == self.STATE_SEARCHING:
rospy.logwarn("在航点 %d 未找到目标,前往下一个航点", self.waypoint_index + 1)
# 计算下一个航点索引
next_index = self.waypoint_index + 1
# 如果还有搜索航点,前往下一个
if next_index <= self.WAYPOINT_SEARCH3: # 航点索引2-4是搜索点
self.navigate_to_waypoint(next_index)
else:
# 没有更多搜索点,前往任务2终点
rospy.logwarn("所有搜索点均未找到目标,前往任务2终点")
self.navigate_to_waypoint(self.WAYPOINT_TASK2_END)
def handle_traffic_light_timeout(self, event):
"""处理交通灯识别超时"""
if self.current_state == self.STATE_TRAFFIC_LIGHT_DETECTION:
rospy.logwarn("交通灯识别超时,执行默认操作")
# 如果在路灯1,默认前往路口1
if self.waypoint_index == self.WAYPOINT_LIGHT1:
rospy.loginfo("默认前往路口1(点9)")
self.navigate_to_waypoint(self.WAYPOINT_CROSS1)
# 如果在路灯2,默认前往路口2
elif self.waypoint_index == self.WAYPOINT_LIGHT2:
rospy.loginfo("默认前往路口2(点11)")
self.navigate_to_waypoint(self.WAYPOINT_CROSS2)
def image_callback(self, data):
"""处理二维码扫描图像"""
if self.current_state != self.STATE_SCANNING:
return
try:
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError as e:
rospy.logerr("图像转换错误: %s", e)
return
# 翻转图像,否则难以识别(亲测)
cv_image = cv2.flip(cv_image, 1)
# 检测二维码
decoded_objects = pyzbar.decode(cv_image)
results = []
for obj in decoded_objects:
data = obj.data.decode('utf-8')
results.append(data)
if results:
result_msg = ", ".join(results)
rospy.loginfo("识别到二维码: %s", result_msg)
self.qr_result_pub.publish(result_msg)
self.qr_detected = True
self.current_state = self.STATE_PLAYING
self.status_pub.publish("PLAYING_AUDIO")
# 取消图像订阅
if self.image_sub:
self.image_sub.unregister()
self.image_sub = None
# 播放音频
self.play_audio(result_msg)
# 导航到任务1出口
self.navigate_to_waypoint(self.WAYPOINT_TASK1_EXIT)
def play_audio(self, qr_code):
"""播放音频文件"""
rospy.loginfo("播放音频: %s", qr_code)
# 查找对应的音频文件
audio_file = None
for key in self.audio_files:
if key in qr_code:
audio_file = self.audio_files[key]
break
if audio_file and os.path.exists(audio_file):
# 播放音频(异步)
threading.Thread(target=self.play_audio_thread, args=(audio_file,)).start()
# 设置二维码结果
if "Fruit" in qr_code:
self.qr_result = 1
elif "Vegetable" in qr_code:
self.qr_result = 2
elif "Dessert" in qr_code:
self.qr_result = 3
else:
rospy.logwarn("未找到匹配的音频文件: %s", qr_code)
def play_audio_thread(self, audio_file):
"""线程中播放音频"""
try:
playsound(audio_file)
rospy.loginfo("音频播放完成")
except Exception as e:
rospy.logerr("音频播放错误: %s", str(e))
def yolo_callback(self, msg):
"""处理YOLO检测结果"""
# 目标搜索状态
if self.current_state == self.STATE_SEARCHING:
# 检查当前类别的有效目标
test1_targets = self.test1_categories.get(self.qr_result, [])
for bbox in msg.bounding_boxes:
if bbox.Class in test1_targets:
rospy.loginfo("发现目标: %s", bbox.Class)
self.target_object = bbox.Class
self.xmin = bbox.xmin
self.ymin = bbox.ymin
self.xmax = bbox.xmax
self.ymax = bbox.ymax
# 更新状态
self.current_state = self.STATE_FOUND_TARGET
self.status_pub.publish("TARGET_FOUND")
# 取消超时定时器
if self.search_timer:
self.search_timer.shutdown()
self.search_timer = None
# 如果尚未订阅图像,则订阅
if not self.image_sub:
self.image_sub = rospy.Subscriber('/usb_cam/image_raw', Image, self.yolo_image_callback)
break
# 交通灯识别状态
elif self.current_state == self.STATE_TRAFFIC_LIGHT_DETECTION:
# 检查交通灯类别
for bbox in msg.bounding_boxes:
if bbox.Class in ['red', 'green']:
rospy.loginfo("识别到交通灯: %s", bbox.Class)
self.traffic_light_result = bbox.Class
self.traffic_light_detected = True
# 取消超时定时器
if self.search_timer:
self.search_timer.shutdown()
self.search_timer = None
# 根据识别结果决定下一步
self.handle_traffic_light_result()
break
def handle_traffic_light_result(self):
"""根据交通灯识别结果决定导航路径并播放音频"""
if self.waypoint_index == self.WAYPOINT_LIGHT1: # 路灯1
if self.traffic_light_result == 'green':
rospy.loginfo("路灯1为绿灯,播放load_1音频并前往路口1(点9)")
# 播放音频
audio_file = self.audio_files.get("load_1")
if audio_file and os.path.exists(audio_file):
threading.Thread(target=self.play_audio_thread, args=(audio_file,)).start()
else:
rospy.logwarn("load_1音频文件不存在!")
# 导航到路口1
self.navigate_to_waypoint(self.WAYPOINT_CROSS1)
else: # 红灯
rospy.loginfo("路灯1为红灯,前往路灯2(点10)")
self.navigate_to_waypoint(self.WAYPOINT_LIGHT2)
elif self.waypoint_index == self.WAYPOINT_LIGHT2: # 路灯2
if self.traffic_light_result == 'green':
rospy.loginfo("路灯2为绿灯,播放load_2音频并前往路口2(点11)")
# 播放音频
audio_file = self.audio_files.get("load_2")
if audio_file and os.path.exists(audio_file):
threading.Thread(target=self.play_audio_thread, args=(audio_file,)).start()
else:
rospy.logwarn("load_2音频文件不存在!")
# 导航到路口2
self.navigate_to_waypoint(self.WAYPOINT_CROSS2)
else: # 红灯
rospy.loginfo("路灯2为红灯,默认前往路口2(点11)")
self.navigate_to_waypoint(self.WAYPOINT_CROSS2)
def yolo_image_callback(self, msg):
"""处理目标跟踪图像"""
# 目标跟踪状态
if self.target_object and self.current_state == self.STATE_FOUND_TARGET:
try:
cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
except CvBridgeError as e:
rospy.logerr("图像转换错误: %s", e)
return
# 翻转图像,否则难以识别(亲测)
cv_image = cv2.flip(cv_image, 1)
# 计算目标位置
target_center_x = (self.xmin + self.xmax) // 2
target_width = self.xmax - self.xmin
frame_center_x = cv_image.shape[1] // 2
# 视觉控制逻辑
twist = Twist()
# 横向控制(转向)
lateral_error = target_center_x - frame_center_x
if abs(lateral_error) > 50:
twist.angular.z = 0.0006 * lateral_error
else:
twist.angular.z = 0.0
# 纵向控制(前进/停止)
if target_width < 200:
twist.linear.x = 0.3
else:
# 到达目标面前
twist.linear.x = 0.0
twist.angular.z = 0.0
rospy.loginfo("已到达目标 %s 面前!", self.target_object)
self.status_pub.publish("ARRIVED_AT_TARGET")
# 播放目标音频
audio_file = self.audio_files.get(self.target_object)
if audio_file and os.path.exists(audio_file):
threading.Thread(target=playsound, args=(audio_file,)).start()
# 停止当前运动
self.cmd_vel_pub.publish(twist)
# 导航到任务2终点
rospy.loginfo("前往任务2终点...")
self.navigate_to_waypoint(self.WAYPOINT_TASK2_END)
# 重置目标状态
self.target_object = None
# 取消图像订阅
if self.image_sub:
self.image_sub.unregister()
self.image_sub = None
# 发布控制命令
self.cmd_vel_pub.publish(twist)
def shutdown(self):
"""节点关闭时的清理工作"""
rospy.loginfo("关闭节点...")
if self.image_sub:
self.image_sub.unregister()
if self.search_timer:
self.search_timer.shutdown()
self.cmd_vel_pub.publish(Twist()) # 停止机器人运动
if __name__ == '__main__':
try:
node = AutomationNode()
rospy.spin()
except rospy.ROSInterruptException:
pass
现在增加任务难度,在抵达任务二的终点时执行一个特殊的任务,任务如下:
1.在抵达任务二的终点时发布一个名为(simulation_start)话题,话题的消息类型为simualtion,该消息类型内部为两个字符串型的数据,内容为str1:'start',str2:qr_result
2.在发送完话题后,就等待,如果接受到名为simulation_result的话题,话题类型为simuilation,该消息类型内部为两个字符串型的数据,内容为str1:'stop',str2的内容不确定(拥有三种可能性分别为A,B,C),根据str2的内容来播放相应的语音,播放完语音后就前往点7门
最新发布