https://github.com/unitreerobotics/xr_teleoperate/blob/main/README_zh-CN.md

 

相机驱动与服务端

https://github.com/unitreerobotics/xr_teleoperate/blob/main/teleop/image_server/image_server.py

其中相机如果是realsense, 安装好驱动后,可以使用命令查看序列号

rs-enumerate-devices

 服务端代码

import cv2
import zmq
import time
import struct
from collections import deque
import numpy as np
import pyrealsense2 as rs
import logging_mp
logger_mp = logging_mp.get_logger(__name__, level=logging_mp.DEBUG)class RealSenseCamera(object):def __init__(self, img_shape, fps, serial_number=None, enable_depth=False) -> None:"""img_shape: [height, width]serial_number: serial number"""self.img_shape = img_shapeself.fps = fpsself.serial_number = serial_numberself.enable_depth = enable_depthalign_to = rs.stream.colorself.align = rs.align(align_to)self.init_realsense()def init_realsense(self):self.pipeline = rs.pipeline()config = rs.config()if self.serial_number is not None:config.enable_device(self.serial_number)config.enable_stream(rs.stream.color, self.img_shape[1], self.img_shape[0], rs.format.bgr8, self.fps)if self.enable_depth:config.enable_stream(rs.stream.depth, self.img_shape[1], self.img_shape[0], rs.format.z16, self.fps)profile = self.pipeline.start(config)self._device = profile.get_device()if self._device is None:logger_mp.error('[Image Server] pipe_profile.get_device() is None .')if self.enable_depth:assert self._device is not Nonedepth_sensor = self._device.first_depth_sensor()self.g_depth_scale = depth_sensor.get_depth_scale()self.intrinsics = profile.get_stream(rs.stream.color).as_video_stream_profile().get_intrinsics()def get_frame(self):frames = self.pipeline.wait_for_frames()aligned_frames = self.align.process(frames)color_frame = aligned_frames.get_color_frame()if self.enable_depth:depth_frame = aligned_frames.get_depth_frame()if not color_frame:return Nonecolor_image = np.asanyarray(color_frame.get_data())# color_image = cv2.cvtColor(color_image, cv2.COLOR_BGR2RGB)depth_image = np.asanyarray(depth_frame.get_data()) if self.enable_depth else Nonereturn color_image, depth_imagedef release(self):self.pipeline.stop()class OpenCVCamera():def __init__(self, device_id, img_shape, fps):"""decive_id: /dev/video* or *img_shape: [height, width]"""self.id = device_idself.fps = fpsself.img_shape = img_shapeself.cap = cv2.VideoCapture(self.id, cv2.CAP_V4L2)self.cap.set(cv2.CAP_PROP_FOURCC, cv2.VideoWriter.fourcc('M', 'J', 'P', 'G'))self.cap.set(cv2.CAP_PROP_FRAME_HEIGHT, self.img_shape[0])self.cap.set(cv2.CAP_PROP_FRAME_WIDTH,  self.img_shape[1])self.cap.set(cv2.CAP_PROP_FPS, self.fps)# Test if the camera can read framesif not self._can_read_frame():logger_mp.error(f"[Image Server] Camera {self.id} Error: Failed to initialize the camera or read frames. Exiting...")self.release()def _can_read_frame(self):success, _ = self.cap.read()return successdef release(self):self.cap.release()def get_frame(self):ret, color_image = self.cap.read()if not ret:return Nonereturn color_imageclass ImageServer:def __init__(self, config, port = 5555, Unit_Test = False):"""config example1:{'fps':30                                                          # frame per second'head_camera_type': 'opencv',                                     # opencv or realsense'head_camera_image_shape': [480, 1280],                           # Head camera resolution  [height, width]'head_camera_id_numbers': [0],                                    # '/dev/video0' (opencv)'wrist_camera_type': 'realsense', 'wrist_camera_image_shape': [480, 640],                           # Wrist camera resolution  [height, width]'wrist_camera_id_numbers': ["218622271789", "241222076627"],      # realsense camera's serial number}config example2:{'fps':30                                                          # frame per second'head_camera_type': 'realsense',                                  # opencv or realsense'head_camera_image_shape': [480, 640],                            # Head camera resolution  [height, width]'head_camera_id_numbers': ["218622271739"],                       # realsense camera's serial number'wrist_camera_type': 'opencv', 'wrist_camera_image_shape': [480, 640],                           # Wrist camera resolution  [height, width]'wrist_camera_id_numbers': [0,1],                                 # '/dev/video0' and '/dev/video1' (opencv)}If you are not using the wrist camera, you can comment out its configuration, like this below:config:{'fps':30                                                          # frame per second'head_camera_type': 'opencv',                                     # opencv or realsense'head_camera_image_shape': [480, 1280],                           # Head camera resolution  [height, width]'head_camera_id_numbers': [0],                                    # '/dev/video0' (opencv)#'wrist_camera_type': 'realsense', #'wrist_camera_image_shape': [480, 640],                           # Wrist camera resolution  [height, width]#'wrist_camera_id_numbers': ["218622271789", "241222076627"],      # serial number (realsense)}"""logger_mp.info(config)self.fps = config.get('fps', 30)self.head_camera_type = config.get('head_camera_type', 'opencv')self.head_image_shape = config.get('head_camera_image_shape', [480, 640])      # (height, width)self.head_camera_id_numbers = config.get('head_camera_id_numbers', [0])self.wrist_camera_type = config.get('wrist_camera_type', None)self.wrist_image_shape = config.get('wrist_camera_image_shape', [480, 640])    # (height, width)self.wrist_camera_id_numbers = config.get('wrist_camera_id_numbers', None)self.port = portself.Unit_Test = Unit_Test# Initialize head camerasself.head_cameras = []if self.head_camera_type == 'opencv':for device_id in self.head_camera_id_numbers:camera = OpenCVCamera(device_id=device_id, img_shape=self.head_image_shape, fps=self.fps)self.head_cameras.append(camera)elif self.head_camera_type == 'realsense':for serial_number in self.head_camera_id_numbers:camera = RealSenseCamera(img_shape=self.head_image_shape, fps=self.fps, serial_number=serial_number)self.head_cameras.append(camera)else:logger_mp.warning(f"[Image Server] Unsupported head_camera_type: {self.head_camera_type}")# Initialize wrist cameras if providedself.wrist_cameras = []if self.wrist_camera_type and self.wrist_camera_id_numbers:if self.wrist_camera_type == 'opencv':for device_id in self.wrist_camera_id_numbers:camera = OpenCVCamera(device_id=device_id, img_shape=self.wrist_image_shape, fps=self.fps)self.wrist_cameras.append(camera)elif self.wrist_camera_type == 'realsense':for serial_number in self.wrist_camera_id_numbers:camera = RealSenseCamera(img_shape=self.wrist_image_shape, fps=self.fps, serial_number=serial_number)self.wrist_cameras.append(camera)else:logger_mp.warning(f"[Image Server] Unsupported wrist_camera_type: {self.wrist_camera_type}")# Set ZeroMQ context and socketself.context = zmq.Context()self.socket = self.context.socket(zmq.PUB)self.socket.bind(f"tcp://*:{self.port}")if self.Unit_Test:self._init_performance_metrics()for cam in self.head_cameras:if isinstance(cam, OpenCVCamera):logger_mp.info(f"[Image Server] Head camera {cam.id} resolution: {cam.cap.get(cv2.CAP_PROP_FRAME_HEIGHT)} x {cam.cap.get(cv2.CAP_PROP_FRAME_WIDTH)}")elif isinstance(cam, RealSenseCamera):logger_mp.info(f"[Image Server] Head camera {cam.serial_number} resolution: {cam.img_shape[0]} x {cam.img_shape[1]}")else:logger_mp.warning("[Image Server] Unknown camera type in head_cameras.")for cam in self.wrist_cameras:if isinstance(cam, OpenCVCamera):logger_mp.info(f"[Image Server] Wrist camera {cam.id} resolution: {cam.cap.get(cv2.CAP_PROP_FRAME_HEIGHT)} x {cam.cap.get(cv2.CAP_PROP_FRAME_WIDTH)}")elif isinstance(cam, RealSenseCamera):logger_mp.info(f"[Image Server] Wrist camera {cam.serial_number} resolution: {cam.img_shape[0]} x {cam.img_shape[1]}")else:logger_mp.warning("[Image Server] Unknown camera type in wrist_cameras.")logger_mp.info("[Image Server] Image server has started, waiting for client connections...")def _init_performance_metrics(self):self.frame_count = 0  # Total frames sentself.time_window = 1.0  # Time window for FPS calculation (in seconds)self.frame_times = deque()  # Timestamps of frames sent within the time windowself.start_time = time.time()  # Start time of the streamingdef _update_performance_metrics(self, current_time):# Add current time to frame times dequeself.frame_times.append(current_time)# Remove timestamps outside the time windowwhile self.frame_times and self.frame_times[0] < current_time - self.time_window:self.frame_times.popleft()# Increment frame countself.frame_count += 1def _print_performance_metrics(self, current_time):if self.frame_count % 30 == 0:elapsed_time = current_time - self.start_timereal_time_fps = len(self.frame_times) / self.time_windowlogger_mp.info(f"[Image Server] Real-time FPS: {real_time_fps:.2f}, Total frames sent: {self.frame_count}, Elapsed time: {elapsed_time:.2f} sec")def _close(self):for cam in self.head_cameras:cam.release()for cam in self.wrist_cameras:cam.release()self.socket.close()self.context.term()logger_mp.info("[Image Server] The server has been closed.")def send_process(self):try:while True:head_frames = []for cam in self.head_cameras:if self.head_camera_type == 'opencv':color_image = cam.get_frame()if color_image is None:logger_mp.error("[Image Server] Head camera frame read is error.")breakelif self.head_camera_type == 'realsense':color_image, depth_iamge = cam.get_frame()if color_image is None:logger_mp.error("[Image Server] Head camera frame read is error.")breakhead_frames.append(color_image)if len(head_frames) != len(self.head_cameras):breakhead_color = cv2.hconcat(head_frames)if self.wrist_cameras:wrist_frames = []for cam in self.wrist_cameras:if self.wrist_camera_type == 'opencv':color_image = cam.get_frame()if color_image is None:logger_mp.error("[Image Server] Wrist camera frame read is error.")breakelif self.wrist_camera_type == 'realsense':color_image, depth_iamge = cam.get_frame()if color_image is None:logger_mp.error("[Image Server] Wrist camera frame read is error.")breakwrist_frames.append(color_image)wrist_color = cv2.hconcat(wrist_frames)# Concatenate head and wrist framesfull_color = cv2.hconcat([head_color, wrist_color])else:full_color = head_colorret, buffer = cv2.imencode('.jpg', full_color)if not ret:logger_mp.error("[Image Server] Frame imencode is failed.")continuejpg_bytes = buffer.tobytes()if self.Unit_Test:timestamp = time.time()frame_id = self.frame_countheader = struct.pack('dI', timestamp, frame_id)  # 8-byte double, 4-byte unsigned intmessage = header + jpg_byteselse:message = jpg_bytesself.socket.send(message)if self.Unit_Test:current_time = time.time()self._update_performance_metrics(current_time)self._print_performance_metrics(current_time)except KeyboardInterrupt:logger_mp.warning("[Image Server] Interrupted by user.")finally:self._close()if __name__ == "__main__":config = {'fps': 30,'head_camera_type': 'opencv','head_camera_image_shape': [480, 1280],  # Head camera resolution'head_camera_id_numbers': [0],'wrist_camera_type': 'opencv','wrist_camera_image_shape': [480, 640],  # Wrist camera resolution'wrist_camera_id_numbers': [2, 4],}server = ImageServer(config, Unit_Test=False)server.send_process()

同一网段的客户端

import cv2
import zmq
import numpy as np
import time
import struct
from collections import deque
from multiprocessing import shared_memory
import logging_mp
logger_mp = logging_mp.get_logger(__name__)class ImageClient:def __init__(self, tv_img_shape = None, tv_img_shm_name = None, wrist_img_shape = None, wrist_img_shm_name = None, image_show = False, server_address = "192.168.123.164", port = 5555, Unit_Test = False):"""tv_img_shape: User's expected head camera resolution shape (H, W, C). It should match the output of the image service terminal.tv_img_shm_name: Shared memory is used to easily transfer images across processes to the Vuer.wrist_img_shape: User's expected wrist camera resolution shape (H, W, C). It should maintain the same shape as tv_img_shape.wrist_img_shm_name: Shared memory is used to easily transfer images.image_show: Whether to display received images in real time.server_address: The ip address to execute the image server script.port: The port number to bind to. It should be the same as the image server.Unit_Test: When both server and client are True, it can be used to test the image transfer latency, \network jitter, frame loss rate and other information."""self.running = Trueself._image_show = image_showself._server_address = server_addressself._port = portself.tv_img_shape = tv_img_shapeself.wrist_img_shape = wrist_img_shapeself.tv_enable_shm = Falseif self.tv_img_shape is not None and tv_img_shm_name is not None:self.tv_image_shm = shared_memory.SharedMemory(name=tv_img_shm_name)self.tv_img_array = np.ndarray(tv_img_shape, dtype = np.uint8, buffer = self.tv_image_shm.buf)self.tv_enable_shm = Trueself.wrist_enable_shm = Falseif self.wrist_img_shape is not None and wrist_img_shm_name is not None:self.wrist_image_shm = shared_memory.SharedMemory(name=wrist_img_shm_name)self.wrist_img_array = np.ndarray(wrist_img_shape, dtype = np.uint8, buffer = self.wrist_image_shm.buf)self.wrist_enable_shm = True# Performance evaluation parametersself._enable_performance_eval = Unit_Testif self._enable_performance_eval:self._init_performance_metrics()def _init_performance_metrics(self):self._frame_count = 0  # Total frames receivedself._last_frame_id = -1  # Last received frame ID# Real-time FPS calculation using a time windowself._time_window = 1.0  # Time window size (in seconds)self._frame_times = deque()  # Timestamps of frames received within the time window# Data transmission quality metricsself._latencies = deque()  # Latencies of frames within the time windowself._lost_frames = 0  # Total lost framesself._total_frames = 0  # Expected total frames based on frame IDsdef _update_performance_metrics(self, timestamp, frame_id, receive_time):# Update latencylatency = receive_time - timestampself._latencies.append(latency)# Remove latencies outside the time windowwhile self._latencies and self._frame_times and self._latencies[0] < receive_time - self._time_window:self._latencies.popleft()# Update frame timesself._frame_times.append(receive_time)# Remove timestamps outside the time windowwhile self._frame_times and self._frame_times[0] < receive_time - self._time_window:self._frame_times.popleft()# Update frame counts for lost frame calculationexpected_frame_id = self._last_frame_id + 1 if self._last_frame_id != -1 else frame_idif frame_id != expected_frame_id:lost = frame_id - expected_frame_idif lost < 0:logger_mp.info(f"[Image Client] Received out-of-order frame ID: {frame_id}")else:self._lost_frames += lostlogger_mp.warning(f"[Image Client] Detected lost frames: {lost}, Expected frame ID: {expected_frame_id}, Received frame ID: {frame_id}")self._last_frame_id = frame_idself._total_frames = frame_id + 1self._frame_count += 1def _print_performance_metrics(self, receive_time):if self._frame_count % 30 == 0:# Calculate real-time FPSreal_time_fps = len(self._frame_times) / self._time_window if self._time_window > 0 else 0# Calculate latency metricsif self._latencies:avg_latency = sum(self._latencies) / len(self._latencies)max_latency = max(self._latencies)min_latency = min(self._latencies)jitter = max_latency - min_latencyelse:avg_latency = max_latency = min_latency = jitter = 0# Calculate lost frame ratelost_frame_rate = (self._lost_frames / self._total_frames) * 100 if self._total_frames > 0 else 0logger_mp.info(f"[Image Client] Real-time FPS: {real_time_fps:.2f}, Avg Latency: {avg_latency*1000:.2f} ms, Max Latency: {max_latency*1000:.2f} ms, \Min Latency: {min_latency*1000:.2f} ms, Jitter: {jitter*1000:.2f} ms, Lost Frame Rate: {lost_frame_rate:.2f}%")def _close(self):self._socket.close()self._context.term()if self._image_show:cv2.destroyAllWindows()logger_mp.info("Image client has been closed.")def receive_process(self):# Set up ZeroMQ context and socketself._context = zmq.Context()self._socket = self._context.socket(zmq.SUB)self._socket.connect(f"tcp://{self._server_address}:{self._port}")self._socket.setsockopt_string(zmq.SUBSCRIBE, "")logger_mp.info("Image client has started, waiting to receive data...")try:while self.running:# Receive messagemessage = self._socket.recv()receive_time = time.time()if self._enable_performance_eval:header_size = struct.calcsize('dI')try:# Attempt to extract header and image dataheader = message[:header_size]jpg_bytes = message[header_size:]timestamp, frame_id = struct.unpack('dI', header)except struct.error as e:logger_mp.warning(f"[Image Client] Error unpacking header: {e}, discarding message.")continueelse:# No header, entire message is image datajpg_bytes = message# Decode imagenp_img = np.frombuffer(jpg_bytes, dtype=np.uint8)current_image = cv2.imdecode(np_img, cv2.IMREAD_COLOR)if current_image is None:logger_mp.warning("[Image Client] Failed to decode image.")continueif self.tv_enable_shm:np.copyto(self.tv_img_array, np.array(current_image[:, :self.tv_img_shape[1]]))if self.wrist_enable_shm:np.copyto(self.wrist_img_array, np.array(current_image[:, -self.wrist_img_shape[1]:]))if self._image_show:height, width = current_image.shape[:2]resized_image = cv2.resize(current_image, (width // 2, height // 2))cv2.imshow('Image Client Stream', resized_image)if cv2.waitKey(1) & 0xFF == ord('q'):self.running = Falseif self._enable_performance_eval:self._update_performance_metrics(timestamp, frame_id, receive_time)self._print_performance_metrics(receive_time)except KeyboardInterrupt:logger_mp.info("Image client interrupted by user.")except Exception as e:logger_mp.warning(f"[Image Client] An error occurred while receiving data: {e}")finally:self._close()if __name__ == "__main__":# example1# tv_img_shape = (480, 1280, 3)# img_shm = shared_memory.SharedMemory(create=True, size=np.prod(tv_img_shape) * np.uint8().itemsize)# img_array = np.ndarray(tv_img_shape, dtype=np.uint8, buffer=img_shm.buf)# img_client = ImageClient(tv_img_shape = tv_img_shape, tv_img_shm_name = img_shm.name)# img_client.receive_process()# example2# Initialize the client with performance evaluation enabled# client = ImageClient(image_show = True, server_address='127.0.0.1', Unit_Test=True) # local testclient = ImageClient(image_show = True, server_address='192.168.123.164', Unit_Test=False) # deployment testclient.receive_process()

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。
如若转载,请注明出处:http://www.pswp.cn/diannao/93852.shtml
繁体地址,请注明出处:http://hk.pswp.cn/diannao/93852.shtml
英文地址,请注明出处:http://en.pswp.cn/diannao/93852.shtml

如若内容造成侵权/违法违规/事实不符,请联系英文站点网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

机械学习中的一些优化算法(以逻辑回归实现案例来讲解)

一、混淆矩阵混淆矩阵是机器学习中评估分类模型性能的重要工具&#xff0c;尤其适用于二分类或多分类任务。它通过展示模型预测结果与实际标签的匹配情况&#xff0c;帮助理解模型的错误类型&#xff08;如假阳性、假阴性等&#xff09;。以下通过二分类场景为例&#xff0c;结…

龙蜥受邀参加2025开放计算技术大会,解码基础模型驱动下的系统创新与生态共建

开放计算技术大会由全球最大的开放计算社区 OCP 发起&#xff0c;是开放计算领域生态覆盖最广且最具影响力的亚洲年度技术盛会。本届大会由 OCP 与 OCTC&#xff08;中国电子工业标准化技术协会开放计算标准工作委员会&#xff09;两大开放组织联合主办&#xff0c;将于 8 月 7…

第三阶段—8天Python从入门到精通【itheima】-140节(pysqark实战——基础准备)

目录 140节——pysqark实战——基础准备 1.学习目标 2.pysqark库的安装 3.pyspark的路径安装问题 一、为什么不需要指定路径&#xff1f; 二、如何找到 pyspark 的具体安装路径&#xff1f; 三、验证一下&#xff1a;直接定位 pyspark 的安装路径 四、总结&#xff1a;记…

数据库中使用SQL作分组处理01(简单分组)

1.简单分组GroupBy什么就Select什么SELECT Name,Score From StudentScore GROUP BY Name,Score2.聚合函数(MAX SUM AVG COUNT)&#xff08;1&#xff09;计算1.表的全部字段都可以用聚合函数&#xff0c;但是筛选聚合函数的结果要用Having关键字2.聚合函数默认排除Null值IDName…

Linux基本服务——web服务解析

提示&#xff1a;文章写完后&#xff0c;目录可以自动生成&#xff0c;如何生成可参考右边的帮助文档 文章目录 目录 Web服务解析 虚拟Web主机 Web目录访问控制 Web服务解析 用途&#xff1a;基于 B/S 架构提供网页的服务端程序 应用层协议&#xff1a;HTTP&#xff08;TCP 80…

深入理解缓存淘汰策略:LRU vs LFU 完全解析

深入理解缓存淘汰策略&#xff1a;LRU vs LFU 完全解析 文章目录深入理解缓存淘汰策略&#xff1a;LRU vs LFU 完全解析前言一、基础概念解析1.1 LRU&#xff08;Least Recently Used&#xff09;- 最近最少使用1.2 LFU&#xff08;Least Frequently Used&#xff09;- 最少使用…

【C语言】字符函数与字符串函数详解

文章目录一、字符分类函数二、字符转换函数三、strlen函数&#xff1a;计算字符串长度功能说明使用示例模拟实现四、strcpy函数&#xff1a;字符串拷贝功能说明模拟实现五、strcat函数&#xff1a;字符串追加功能说明模拟实现六、strcmp函数&#xff1a;字符串比较比较规则模拟…

uvicorn 启动重复加载 多次加载

目录 uvicorn 启动重复加载 多次加载 解决方法1&#xff1a; 解决方法2&#xff1a; uvicorn 启动重复加载 多次加载 fastapi_aa 是当前类 解决方法1&#xff1a; import uvicornfrom fastapi import FastAPIapp FastAPI()if __name__ "__main__":if sys.gett…

Bard AI本地部署教程:在自己的服务器上运行谷歌AI

Bard AI本地部署教程:在自己的服务器上运行谷歌AI 关键词:Bard AI、本地部署、服务器、谷歌AI、运行教程 摘要:本文旨在为大家详细介绍如何在自己的服务器上实现Bard AI的本地部署。我们会从背景知识讲起,逐步深入到核心概念、算法原理、操作步骤,还会提供项目实战案例和实…

应急响应处置案例(上)

本文目录 目录 本文目录 Web安全事件 概述 案例1 - webshell 背景 排查情况 天眼 服务器 案例2 - Struts2 排查情况 天眼 服务器 案例3 - Redis未授权 背景 排查情况 天眼 服务器 案例4 - EW内网穿透 背景 排查情况 天眼 服务器 案例5 - 一句话木马 背…

面试官问我:“为什么不能完全用对象替代指针?”我笑了:看看Google和Linux内核代码就知道了!

本篇摘要 本篇将以最通俗易懂的语言&#xff0c;形象的讲述为什么很多情境下&#xff0c;我们优先考虑的使用指针而不是对象本身&#xff0c;本篇将给出你答案&#xff01; 一.从一个生活例子说起&#xff0c;形象秒懂 想象一下&#xff0c;你去图书馆借书&#xff0c;下面你…

CAMx大气污染模拟全流程:Linux编译/多重嵌套配置/SMOKE清单预处理/SA-DDM-PA工具应用与科研绘图结果可视化分析

CAMx模型是一个基于大气化学&#xff0c;针对臭氧、颗粒物和雾霾天气过程的大气污染物计算模型。【目标】&#xff1a;1、掌握CAMx模式的区域空气质量模拟案例配置技术方法2、掌握SMOKE模型的CAMx模式大气排放清单输入准备方法3、掌握CAMx模式污染来源解析工具&#xff08;SA&a…

嵌入式学习笔记-MCU阶段-DAY10ESP8266模块

1.ESP8266概述 官方网址&#xff1a;ESP8266 Wi-Fi MCU I 乐鑫科技 (espressif.com.cn) ESP8266模块---wifi模块 产品特点&#xff1a; 2.ESP8266中的wifi: ESP8266EX ⽀持 TCP/IP 协议&#xff0c;完全遵循 802.11 b/g/n WLAN MAC 协议&#xff0c;⽀持分布式控制功能 (DC…

如何快速通过软件项目验收,第三方软件检测机构的重要性

在客户和开发团队之间&#xff0c;最后临门一脚的项目验收环节总容易出现各种问题&#xff0c;以至于时间无限拉长&#xff0c;久久不见结束&#xff0c;为此给大家准备了一份如何快速通过软件项目验收的内容来帮助大家结束持久战。 一、项目验收准备材料 &#xff08;一&…

洛谷做题3:P5711 【深基3.例3】闰年判断

文章目录题目描述输入格式输出格式输入输出样例分析代码题目描述 输入一个年份&#xff0c;判断这一年是否是闰年&#xff0c;如果是输出 1&#xff0c;否则输出 0。 1582 年以来&#xff0c;闰年的定义&#xff1a; 普通闰年&#xff1a;公历年份是 4 的倍数&#xff0c;且不…

PMP证书可以挂靠吗?怎么挂靠?

哈喽学弟学妹们&#xff0c;作为过来人&#xff0c;今天想跟大家聊聊 PMP 证书挂靠这事儿 —— 可能不少准备考或者刚考完的同学都琢磨过&#xff0c;但学长得跟你们交个底&#xff1a;这事儿真不行&#xff0c;更别提啥挂靠费了。先说说 PMP 证书本身哈&#xff0c;它是美国 P…

91-基于Spark的空气质量数据分析可视化系统

基于Spark的空气质量数据分析可视化系统设计与实现 项目概述 本项目是一个基于Apache Spark的大数据分析和可视化系统&#xff0c;专门用于空气质量数据的采集、分析、预测和可视化展示。系统采用分布式计算架构&#xff0c;结合机器学习算法&#xff0c;实现了对全国12个主要…

leetcode 2419. 按位与最大的最长子数组 中等

给你一个长度为 n 的整数数组 nums 。考虑 nums 中进行 按位与&#xff08;bitwise AND&#xff09;运算得到的值 最大 的 非空 子数组。换句话说&#xff0c;令 k 是 nums 任意 子数组执行按位与运算所能得到的最大值。那么&#xff0c;只需要考虑那些执行一次按位与运算后等于…

Git 命令使用指南:从入门到进阶

目录1. Git 基本操作1.1 添加文件到暂存区1.2 提交更改到本地仓库1.3 查看工作区状态1.4 查看提交历史1.5 查看引用日志&#xff08;包括已删除的记录&#xff09;2. 版本回退与撤销2.1 版本回退2.2 查看已删除的提交记录3. 分支管理3.1 查看分支3.2 创建并切换到新分支3.3 合并…

SQL数据库连接Python实战:疫情数据指挥中心搭建指南

SQL数据库连接Python实战&#xff1a;疫情数据指挥中心搭建指南从WHO数据集到实时仪表盘&#xff0c;构建工业级疫情监控系统一、疫情数据指挥中心&#xff1a;全球健康危机的中枢神经​​疫情数据价值​​&#xff1a;全球每日新增病例&#xff1a;50万疫苗接种数据&#xff1…