feat: 正确终止服务器(疑似)

This commit is contained in:
zpff 2025-08-14 17:37:46 +08:00
parent 2ce41b8372
commit 81eed99a03
2 changed files with 18 additions and 3 deletions

View File

@ -95,7 +95,7 @@ class GazeboSimHttpServer(HttpRPCServer):
# 启动roscore # 启动roscore
self.roscore_proc = subprocess.Popen( self.roscore_proc = subprocess.Popen(
['roscore'], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) ['roscore'], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL)
time.sleep(2) time.sleep(5)
rospy.init_node('gazebo_world_manager', anonymous=True) rospy.init_node('gazebo_world_manager', anonymous=True)
# 添加接口 # 添加接口
@ -259,6 +259,22 @@ class GazeboSimHttpServer(HttpRPCServer):
print('Server remove model done.') print('Server remove model done.')
return jsonify(ret) return jsonify(ret)
def shutdown(self):
"""
关闭所有资源
"""
# 1. 关闭场景(如果正在运行)
if self.scene_mgr.running_scene:
self.shut_scene()
# 2. 关闭 HeartbeatServer
self.heartbeat_server.stop()
# 3. 关闭 roscore 进程
if self.roscore_proc:
self.roscore_proc.terminate()
self.roscore_proc.wait()
# 4. 关闭 Flask HTTP 服务器
super().stop()
print("GazeboSimHttpServer stopped.")
if __name__ == '__main__': if __name__ == '__main__':
server = GazeboSimHttpServer() server = GazeboSimHttpServer()

View File

@ -6,8 +6,7 @@ from http_server import GazeboSimHttpServer
server = GazeboSimHttpServer() server = GazeboSimHttpServer()
def signal_handler(sig, frame): def signal_handler(sig, frame):
print('Exiting...') server.shutdown()
server.stop()
sys.exit(0) sys.exit(0)
signal.signal(signal.SIGINT, signal_handler) signal.signal(signal.SIGINT, signal_handler)