这个问题是,Flask显示ROS消息时,ROS需要在主线程中调用,但是Flask把ROS放在分线程上了,
参看文档ROS与Python入门教程-节点初始化和关闭
找到
rospy.init_node(name, anonymous=False, log_level=rospy.INFO, disable_signals=False)
可以看到
disable_signals=False,默认rospy注册信号处理器以便可以使用ctrl+c来退出。下面的情况下,你可以禁止:
- 不是从python的主线程调用init_node()。
- python只允许主线程注册信号处理器。
- 在wxPython或其他GUI工具运行rospy,它们有自己的退出处理。
- 你希望默认使用自己的信号处理器。
在rospy.init_node将disable_signals设为True即可
补充
这里把ros和flask相关的代码也贴上来吧
参考flask-ros
代码结构
├── app.py
└── templates
└── index.html
app.py
#!/usr/bin/env python
import rospy
import cv2
from threading import Thread, Event
from flask import Flask, render_template, Response
import signal, sys
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
frame = None
bridge = CvBridge()
event = Event()
def on_image(msg):
global frame
#cv_image = cv2.flip(cv2.flip(bridge.imgmsg_to_cv2(msg, desired_encoding = "passthrough"),0),1)
cv_image = cv2.rotate(bridge.imgmsg_to_cv2(msg, desired_encoding = "passthrough"), cv2.ROTATE_90_CLOCKWISE)
frame = cv2.imencode(".jpg",cv_image)[1].tobytes()
event.set()
Thread(target=lambda: rospy.init_node('cam_listener', disable_signals=True)).start()
rospy.Subscriber("/camera/image_raw",Image, on_image)
app = Flask(__name__)
def get_frame():
event.wait()
event.clear()
return frame
@app.route('/')
def index():
return render_template('index.html')
def gen():
while True:
frame = get_frame()
yield (b'--frame\r\n'
b'Content-Type: image/jpeg\r\n\r\n' + frame + b'\r\n')
@app.route('/video_feed')
def video_feed():
return Response(gen(),
mimetype='multipart/x-mixed-replace; boundary=frame')
def signal_handler(signal, frame):
rospy.signal_shutdown("end")
sys.exit(0)
signal.signal(signal.SIGINT,signal_handler)
if __name__ == '__main__':
app.run(host='0.0.0.0', port=8080 ,debug=True)
index.html
<html>
<head>
<title>Camera Stream</title>
</head>
<body>
<img src="{{ url_for('video_feed') }}">
</body>
</html>