实现逻辑很简单,Carla有支持更改信号灯和读取信号灯的功能,通过自定义消息读取Carla信号状态并发布给信号灯,信号灯接收并发布指令,反过来也是一样的。
一、话题通信
信号灯与Carla之间通过ROS话题进行通信,消息是自定义的:
# TrafficLights.msg
float64 timestamp
uint32 traffic_id
uint32 light
二、Carla交通灯→信号灯
我提取了第1个交通灯进行发布,并显示灯的位置,代码如下:
#!/usr/bin/env python3
import rospy
from traffic_ros.msg import TrafficLights
import carla
def show_point(world, point_location):
world.debug.draw_string(point_location, 'X', draw_shadow=False,
color=carla.Color(r=0, g=255, b=0), life_time=50,
persistent_lines=True)
def main():
# 连接到CARLA仿真器
rospy.init_node('traffic_light_publisher', anonymous=True)
pub = rospy.Publisher('traffic_sub', TrafficLights, queue_size=10)
client = carla.Client('localhost', 2000)
client.set_timeout(5.0) # 设置超时时间
# 获取世界对象和地图
world = client.get_world()
map = world.get_map()
# 获取所有存在的交通信号灯
traffic_lights = world.get_actors().filter('traffic.traffic_light')
# 获取第一个交通信号灯的位置
if len(traffic_lights) > 0:
traffic_light = traffic_lights[0] # 如果你需要获取第一个信号灯位置,索引应该为0而不是1
location = traffic_light.get_location()
print("交通信号灯位置: ", location)
else:
print("未找到交通信号灯")
# 在地图中可视化信号灯位置
show_point(world, location)
# 发布频率
rate = rospy.Rate(1)
while not rospy.is_shutdown():
# 输出信号状态
state = traffic_light.get_state()
if state == carla.TrafficLightState.Red:
state_value = 0
elif state == carla.TrafficLightState.Green:
state_value = 1
elif state == carla.TrafficLightState.Yellow:
state_value = 2
traffic_msg = TrafficLights()
traffic_msg.timestamp = rospy.get_time()
traffic_msg.traffic_id = traffic_light.id
traffic_msg.light = state_value
pub.publish(traffic_msg)
print(traffic_msg)
# rospy.loginfo("发布信号灯状态: %s", state_value)
rate.sleep()
world.tick()
if __name__ == '__main__':
try:
mai