Coppelia Sim (v-REP)仿真 机器人3D相机手眼标定与实时视觉追踪 (二)

coppelia sim[V-REP]仿真实现 机器人于3D相机手眼标定与实时视觉追踪 二

  • zmq API接口python调用
  • python获取3D相机的数据
    • 获取彩色相机的数据
    • 获取深度相机的数据
    • 用matpolit显示
  • python控制机器人运动
      • 直接控制轴的位置
      • 用IK运动学直接移动到末端姿态
  • 相机内参的标定
    • 记录拍照点的位置
    • 标定板大小的及坐标的设置
      • 初始化获取相关的资源句柄
    • 机器人运动参数设置
    • 进行拍照和内参标定
    • 内参标定结果及标定板的姿态显示
    • 进行手眼标定
      • 参数说明
      • 标定结果说明

Coppelia Sim (v-REP)仿真 机器人3D相机手眼标定与实时视觉追踪 (一)

zmq API接口python调用

在官方提供的例子里面已经包含了调用的例子程序,把coppeliasim_zmqremoteapi_client 文件夹拷贝过来就直接可以用

import time
# from zmqRemoteApi import RemoteAPIClient
from coppeliasim_zmqremoteapi_client import RemoteAPIClientdef myFunc(input1, input2):print('Hello', input1, input2)return 21print('Program started')client = RemoteAPIClient()
sim = client.require('sim')# Create a few dummies and set their positions:
handles = [sim.createDummy(0.01, 12 * [0]) for _ in range(50)]
for i, h in enumerate(handles):sim.setObjectPosition(h, -1, [0.01 * i, 0.01 * i, 0.01 * i])# Run a simulation in asynchronous mode:
sim.startSimulation()
while (t := sim.getSimulationTime()) < 3:s = f'Simulation time: {t:.2f} [s] (simulation running asynchronously '\'to client, i.e. non-stepping)'print(s)sim.addLog(sim.verbosity_scriptinfos, s)

python获取3D相机的数据

获取彩色相机的数据

	visionSensorHandle = sim.getObject('/UR5/3D_camera')img, [resX, resY] = sim.getVisionSensorImg(visionSensorHandle)img = np.frombuffer(img, dtype=np.uint8).reshape(resY, resX, 3)# In CoppeliaSim images are left to right (x-axis), and bottom to top (y-axis)# (consistent with the axes of vision sensors, pointing Z outwards, Y up)# and color format is RGB triplets, whereas OpenCV uses BGR:img = cv2.flip(cv2.cvtColor(img, cv2.COLOR_BGR2RGB), 0)

获取深度相机的数据

	deepSensorHandle = sim.getObject('/UR5/3D_camera/depth')# 获取深度图像Deepdate = sim.getVisionSensorDepth(deepSensorHandle, 1)# 解包为浮点数数组num_floats = Deepdate[1][0] * Deepdate[1][1]depth_data = struct.unpack(f'{num_floats}f', Deepdate[0])# 将数据转为 numpy 数组depth_array = np.array(depth_data)depth_image = depth_array.reshape((Deepdate[1][1],  Deepdate[1][0]))depth_image = np.flipud(depth_image)deepcolor = encoding.FloatArrayToRgbImage(depth_image, scale_factor=256*3.5*1000)

用matpolit显示

class ImageStreamDisplay:def __init__(self, resolution):# 创建一个包含两个子图的图形self.fig, (self.ax1, self.ax2) = plt.subplots(1, 2, figsize=(10, 6))  # 1行2列# 设置子图的标题self.ax1.set_title('RGB img')self.ax2.set_title('Depth img')# 初始化两个图像显示对象,使用零数组作为占位符,并设置animated=True以启用动画self.im_display1 = self.ax1.imshow(np.zeros([resolution[1], resolution[0], 3]), animated=True)self.im_display2 = self.ax2.imshow(np.zeros([resolution[1], resolution[0]]), animated=True, cmap='gray', vmin=0, vmax=3.5)# 自动调整子图布局以避免重叠self.fig.tight_layout()# 开启交互模式plt.ion()# 显示图形plt.show()def displayUpdated(self, rgbBuffer1, rgbBuffer2):# 更新两个图像显示对象# 注意:对于imshow,通常使用set_data而不是set_arrayself.im_display1.set_data(rgbBuffer1)self.im_display2.set_data(rgbBuffer2)# plt.colorbar()# 刷新事件并暂停以更新显示self.fig.canvas.flush_events()plt.pause(0.01)  # 暂停一小段时间以允许GUI更新display = ImageStreamDisplay([640, 480])display.displayUpdated(img, depth_image)

显示的效果
在这里插入图片描述

python控制机器人运动

直接控制轴的位置

def moveToConfig(robotColor, handles, maxVel, maxAccel, maxJerk, targetConf):sim = robotColorcurrentConf = []for i in range(len(handles)):currentConf.append(sim.getJointPosition(handles[i]))params = {}params['joints'] = handlesparams['targetPos'] = targetConfparams['maxVel'] = maxVelparams['maxAccel'] = maxAccelparams['maxJerk'] = maxJerk# one could also use sim.moveToConfig_init, sim.moveToConfig_step and sim.moveToConfig_cleanupsim.moveToConfig(params)

用IK运动学直接移动到末端姿态

def MovetoPose(robothandle, maxVel, maxAccel, maxJerk, targetpost):sim = robothandleparams['ik'] = {'tip': tipHandle, 'target': targetHandle}# params['object'] = targetHandleparams['targetPose'] = targetpostparams['maxVel'] = maxVelparams['maxAccel'] = maxAccelparams['maxJerk'] = maxJerksim.moveToPose(params)

相机内参的标定

记录拍照点的位置

targetjoinPos1 = [0 * math.pi / 180, 45 * math.pi / 180, -60 *math.pi / 180, 0 * math.pi / 180, 90 * math.pi / 180, 0 * math.pi / 180]
targetPos = []targetPos1 = [-0.1100547923916193, -0.01595811170705489, 0.8466254222789784,0.560910589456253, -0.5609503047415633, 0.4305463900323013, 0.43051582116844406]
targetPos2 = [-0.16595811170705488, -0.01595811170705487, 0.8216254222789784,0.5417925804901749, -0.4495188049772251, 0.575726166263469, 0.415852167455231]
targetPos3 = [-0.1100547923916193, -0.01595811170705487, 0.8216254222789784,3.21292597227468e-05, 0.7932742610364036, -0.6088644721541127, 1.7127530004424877e-05]
targetPos4 = [-0.1100547923916193, -0.01595811170705489, 0.9216254222789784,1.4077336111962496e-05, 0.7932754374087434, -0.608862940314109, 1.085602215830202e-05]
targetPos5 = [-0.1100547923916193, -0.015958111707054884, 0.8216254222789784,0.579152193496431, -0.5416388515007398, 0.4546027806731813, 0.40564319680902283]
targetPos6 = [-0.1100547923916193, -0.015958111707054884, 0.8216254222789784,0.5415953148716405, -0.5791980963813808, 0.4056650408034863, 0.45457667640033966]
targetPos7 = [-0.2100547923916193, -0.015958111707054898, 0.8816254222789784,0.5212515544329563, -0.5212938037943111, 0.4777945964218841, 0.47776763259657323]
targetPos8 = [-0.15000547923916193, -0.015958111707054898, 0.8016254222789784,0.5212515544329563, -0.5212938037943111, 0.4777945964218841, 0.47776763259657323]
targetPos9 = [-0.15000547923916193, -0.015958111707054898, 0.8016254222789784,0.5212515544329563, -0.5212938037943111, 0.4777945964218841, 0.47776763259657323]
targetPos10 = [-0.1010000547923916193, -0.015958111707054898, 0.8016254222789784,0.5212515544329563, -0.5212938037943111, 0.4777945964218841, 0.47776763259657323]
targetPos11 = []
targetPos12 = []
targetPos.append(targetPos1)
targetPos.append(targetPos2)
targetPos.append(targetPos3)
targetPos.append(targetPos4)
targetPos.append(targetPos5)
targetPos.append(targetPos6)
targetPos.append(targetPos7)
targetPos.append(targetPos8)
targetPos.append(targetPos9)
targetPos.append(targetPos10)

标定板大小的及坐标的设置

# 设置棋盘格规格(内角点的数量)
chessboard_size = (10, 7)# 3D 世界坐标的点准备(标定板的真实物理尺寸)
square_size = 0.015  # 假设每个格子的边长是15毫米(可以根据实际情况调整)
objp = np.zeros((chessboard_size[0]*chessboard_size[1], 3), np.float32)
objp[:, :2] = np.mgrid[0:chessboard_size[0],0:chessboard_size[1]].T.reshape(-1, 2) * square_size# 储存所有图片的3D点和2D点
objpoints = []  # 3D 点 (真实世界空间坐标)
imgpoints = []  # 2D 点 (图像平面中的点)
robot_poses_R = []  # 10 个旋转矩阵
robot_poses_t = []  # 10 个平移向量
camera_poses_R = []  # 10 个相机的旋转矩阵
camera_poses_t = []  # 10 个相机的平移向量

初始化获取相关的资源句柄

targetHandle = sim.getObject('/UR5/Target')
tipHandle = sim.getObject('/UR5/Tip')
robotHandle = sim.getObject('/UR5')visionSensorHandle = sim.getObject('/UR5/3D_camera')
deepSensorHandle = sim.getObject('/UR5/3D_camera/depth')
chessboardHandle = sim.getObject('/Plane')jointHandles = []
for i in range(6):jointHandles.append(sim.getObject('/UR5/joint', {'index': i}))

机器人运动参数设置

jvel = 310 * math.pi / 180
jaccel = 100 * math.pi / 180
jjerk = 80 * math.pi / 180jmaxVel = [jvel, jvel, jvel, jvel, jvel, jvel]
jmaxAccel = [jaccel, jaccel, jaccel, jaccel, jaccel, jaccel]
jmaxJerk = [jjerk, jjerk, jjerk, jjerk, jjerk, jjerk]vel = 30
accel = 1.0
jerk = 1maxVel = [vel, vel, vel, vel]
maxAccel = [accel, accel, accel, accel]
maxJerk = [jerk, jerk, jerk, jerk]

进行拍照和内参标定

print('------Perform camera calibration------')
# 初始拍照位置
moveToConfig(sim, jointHandles, jmaxVel, jmaxAccel, jmaxJerk, targetjoinPos1)
index = 0
for i in range(10):goalTr = targetPos[i].copy()params = {}params['ik'] = {'tip': tipHandle, 'target': targetHandle}# params['object'] = targetHandleparams['targetPose'] = goalTrparams['maxVel'] = maxVelparams['maxAccel'] = maxAccelparams['maxJerk'] = maxJerksim.moveToPose(params)# 这里是尝试转动角度的# EulerAngles=sim.getObjectOrientation(targetHandle,tipHandle)# # EulerAngles[1]+=15* math.pi / 180# EulerAngles[0]+=25* math.pi / 180# sim.setObjectOrientation(targetHandle,EulerAngles,tipHandle)# goalTr=sim.getObjectPose(targetHandle,robotHandle)# # goalTr[0]=goalTr[1]-0.15# params = {}# params['ik'] = {'tip': tipHandle, 'target': targetHandle}# # params['object'] = targetHandle# params['targetPose'] = goalTr# params['maxVel'] = maxVel# params['maxAccel'] = maxAccel# params['maxJerk'] = maxJerk# sim.moveToPose(params)img, [resX, resY] = sim.getVisionSensorImg(visionSensorHandle)img = np.frombuffer(img, dtype=np.uint8).reshape(resY, resX, 3)# In CoppeliaSim images are left to right (x-axis), and bottom to top (y-axis)# (consistent with the axes of vision sensors, pointing Z outwards, Y up)# and color format is RGB triplets, whereas OpenCV uses BGR:img = cv2.flip(cv2.cvtColor(img, cv2.COLOR_BGR2RGB), 0)# img=cv2.cvtColor(img, cv2.COLOR_BGR2RGB)gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)# 找到棋盘格的角点ret, corners = cv2.findChessboardCorners(gray, chessboard_size, None)# 如果找到角点,添加到点集if ret == True:objpoints.append(objp)imgpoints.append(corners)# 显示角点img = cv2.drawChessboardCorners(img, chessboard_size, corners, ret)# 使用 solvePnP 获取旋转向量和平移向量# ret, rvec, tvec = cv2.solvePnP(objpoints, imgpoints, camera_matrix, dist_coeffs)# 获取深度图像Deepdate = sim.getVisionSensorDepth(deepSensorHandle, 1)# 解包为浮点数数组num_floats = Deepdate[1][0] * Deepdate[1][1]depth_data = struct.unpack(f'{num_floats}f', Deepdate[0])# 将数据转为 numpy 数组depth_array = np.array(depth_data)depth_image = depth_array.reshape((Deepdate[1][1],  Deepdate[1][0]))depth_image = np.flipud(depth_image)deepcolor = encoding.FloatArrayToRgbImage(depth_image, scale_factor=256*3.5*1000)display.displayUpdated(img, depth_image)# 进行相机标定
ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None)# 计算标定的误差
total_error = 0
errors = []
# 遍历每张图像
for objp, imgp, rvec, tvec in zip(objpoints, imgpoints, rvecs, tvecs):# 将三维物体点转换为相机坐标系下的二维图像点projected_imgpoints, _ = cv2.projectPoints(objp, rvec, tvec, mtx, dist)# 计算原始 imgpoints 和 projected_imgpoints 之间的误差error = cv2.norm(imgp, projected_imgpoints, cv2.NORM_L2) / \len(projected_imgpoints)errors.append(error)total_error += error# 计算所有图像的平均误差
mean_error = total_error / len(objpoints)# 打印每幅图像的误差
for i, error in enumerate(errors):print(f"图像 {i+1} 的误差: {error}")# 打印平均误差
print(f"所有图像的平均误差: {mean_error}")# 打印相机内参和畸变系数
print("Camera Matrix:\n", mtx)
print("Distortion Coefficients:\n", dist)
print('camera carlibraed Done')fig = plt.figure()
ax = fig.add_subplot(111, projection='3d')

内参标定结果及标定板的姿态显示

------Perform camera calibration------
图像 1 的误差: 0.02561960222938916
图像 2 的误差: 0.029812235820557646
图像 3 的误差: 0.025746131185086674
图像 4 的误差: 0.026949289915749124
图像 5 的误差: 0.02779773110640927
图像 6 的误差: 0.02970027985427542
图像 7 的误差: 0.02793374910087122
图像 8 的误差: 0.025625364208011148
图像 9 的误差: 0.02599937961290829
图像 10 的误差: 0.028105922281836906
所有图像的平均误差: 0.027328968531509484
Camera Matrix:[[581.55412313   0.         317.88732972][  0.         581.24563369 240.0350863 ][  0.           0.           1.        ]]
Distortion Coefficients:[[-0.0309966   0.15304087  0.00125555 -0.00093788 -0.27333318]]
camera carlibraed Done

在这里插入图片描述

进行手眼标定

参数说明

相机坐标系下的点可以根据内参标定的结果,使用solvePnP,获取棋盘格在相机坐标下的3D点,用sim.getObjectPose获取到机器人的姿态

print('------Perform hand-eye calibration------')
# 初始拍照位置
moveToConfig(sim, jointHandles, jmaxVel, jmaxAccel, jmaxJerk, targetjoinPos1)for i in range(10):goalTr = targetPos[i].copy()# goalTr[2] = goalTr[2] - 0.2params = {}params['ik'] = {'tip': tipHandle, 'target': targetHandle}# params['object'] = targetHandleparams['targetPose'] = goalTrparams['maxVel'] = maxVelparams['maxAccel'] = maxAccelparams['maxJerk'] = maxJerksim.moveToPose(params)img, [resX, resY] = sim.getVisionSensorImg(visionSensorHandle)img = np.frombuffer(img, dtype=np.uint8).reshape(resY, resX, 3)# In CoppeliaSim images are left to right (x-axis), and bottom to top (y-axis)# (consistent with the axes of vision sensors, pointing Z outwards, Y up)# and color format is RGB triplets, whereas OpenCV uses BGR:img = cv2.flip(cv2.cvtColor(img, cv2.COLOR_BGR2RGB), 0)# img=cv2.cvtColor(img, cv2.COLOR_BGR2RGB)gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)# 找到棋盘格的角点ret, corners = cv2.findChessboardCorners(gray, chessboard_size, None)# 如果找到角点,添加到点集if ret == True:# 使用 solvePnP 获取旋转向量和平移向量ret, rvec, tvec = cv2.solvePnP(objp, corners, mtx, dist)# 将 rvec 转换为旋转矩阵R, _ = cv2.Rodrigues(rvec)camera_tvec_matrix = tvec.reshape(-1)# 获取到机器人夹爪的姿态Targetpost = sim.getObjectPose(tipHandle)pose_matrix = sim.poseToMatrix(Targetpost)# 提取旋转矩阵 (3x3)robot_rotation_matrix = np.array([[pose_matrix[0], pose_matrix[1], pose_matrix[2]],[pose_matrix[4], pose_matrix[5], pose_matrix[6]],[pose_matrix[8], pose_matrix[9], pose_matrix[10]]])# 提取平移向量 (P0, P1, P2)robot_tvec_matrix = np.array([pose_matrix[3], pose_matrix[7], pose_matrix[11]])# 加入到手眼标定数据robot_poses_R.append(robot_rotation_matrix)robot_poses_t.append(robot_tvec_matrix)camera_poses_R.append(R)camera_poses_t.append(camera_tvec_matrix)img = draw_axes(img, mtx, dist, rvec, tvec, 0.015*7)# 获取深度图像Deepdate = sim.getVisionSensorDepth(deepSensorHandle, 1)# 解包为浮点数数组num_floats = Deepdate[1][0] * Deepdate[1][1]depth_data = struct.unpack(f'{num_floats}f', Deepdate[0])# 将数据转为 numpy 数组depth_array = np.array(depth_data)depth_image = depth_array.reshape((Deepdate[1][1],  Deepdate[1][0]))depth_image = np.flipud(depth_image)deepcolor = encoding.FloatArrayToRgbImage(depth_image, scale_factor=256*3.5*1000)display.displayUpdated(img, depth_image)print("开始手眼标定...")
R_cam2gripper, t_cam2gripper = cv2.calibrateHandEye(robot_poses_R, robot_poses_t, camera_poses_R, camera_poses_t, method=cv2.CALIB_HAND_EYE_TSAI
)camera_pose_intip = sim.getObjectPose(visionSensorHandle, tipHandle)
camera_matrix_intip = sim.poseToMatrix(camera_pose_intip)
eulerAngles = sim.getEulerAnglesFromMatrix(camera_matrix_intip)print("相机到机器人末端的旋转矩阵:\n", R_cam2gripper)
print("相机到机器人末端的平移向量:\n", t_cam2gripper)

标定结果说明

开始手眼标定...
相机到机器人末端的旋转矩阵:[[ 0.00437374 -0.99998866  0.00188594][ 0.99998691  0.00436871 -0.00266211][ 0.00265384  0.00189756  0.99999468]]
相机到机器人末端的平移向量:[[ 0.04918588][-0.00012231][ 0.00194761]]
手眼标定完成

在虚拟环境中量出的结果和相机的标定结果,由于图像的坐标系和Sim的坐标系的坐标轴是相差90°,所有顺序不一样
在这里插入图片描述

接下来使用标定好的结果进行跟踪标定板的位置

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

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

相关文章

Linux 安装nacos

1.下载版本 https://github.com/alibaba/nacos/tags 2.解压压缩包&#xff0c;启动 (1)将压缩包放到/usr/local目录下&#xff0c;解压 tar -xvf nacos-server-2.0.0-BETA.tar.gz(2)删除压缩包 rm -f nacos-server-2.0.0-BETA.tar.gz(3) 找到nacos的mysql的数据库脚本,在数…

sqoop问题汇总记录

此篇博客仅记录在使用sqoop时遇到的各种问题。持续更新&#xff0c;有问题评论区一起探讨&#xff0c;写得有不足之处见谅。 Oracle_to_hive 1. main ERROR Could not register mbeans java.security.AccessControlException: access denied ("javax.management.MBeanTr…

基于微信小程序的小区管理系统设计与实现(lw+演示+源码+运行)

摘 要 社会发展日新月异&#xff0c;用计算机应用实现数据管理功能已经算是很完善的了&#xff0c;但是随着移动互联网的到来&#xff0c;处理信息不再受制于地理位置的限制&#xff0c;处理信息及时高效&#xff0c;备受人们的喜爱。所以各大互联网厂商都瞄准移动互联网这个潮…

window11使用wsl2安装Ubuntu22.04

目录 1、快速了解wsl2 安装子系统linux流程&#xff08;B站视频&#xff09; 2、wsl2常用命令 3、windows与子系统Linux文件访问方法 4、子系统linux使用windows网络代理、网络配置&#xff08;镜像网络&#xff0c;非NAT&#xff09; 5、wsl2 Ubuntu miniconda 安装 6、…

【K8S系列】Kubernetes 中 NodePort 类型的 Service 无法访问的问题【已解决】

在 Kubernetes 中&#xff0c;NodePort 类型的 Service 允许用户通过每个节点的 IP 地址和指定的端口访问应用程序。如果 NodePort 类型的 Service 无法通过节点的 IP 地址和指定端口进行访问&#xff0c;可能会导致用户无法访问应用。本文将详细分析该问题的常见原因及其解决方…

Cyber​​Panel filemanager/upload 远程命令执行漏洞复现

0x01 产品简介 CyberPanel是一个开源的Web控制面板,它提供了一个用户友好的界面,用于管理网站、电子邮件、数据库、FTP账户等。CyberPanel旨在简化网站管理任务,使非技术用户也能轻松管理自己的在线资源。 0x02 漏洞概述 该漏洞源于filemanager/upload接口未做身份验证和…

(C#面向初学者的 .NET 的生成 AI) 第 2 部分-什么是 AI 和 ML?

从本部分开始Luis Quintanilla介绍AI和机器学习&#xff0c;需要学习的一些东西是什么是AI和ML&#xff1f;作为一名.net开发人员如何学习使用AI和ML。 1、首先什么是AI 和 ML&#xff1f; 你可以把它看作是基本相同事物的不同层次。 在顶层的是AI&#xff08;人工智能&#xf…

Swarm-LIO: Decentralized Swarm LiDAR-inertial Odometry论文翻译

文章目录 前言一、介绍二、相关工作三、方法A. 问题表述B. 框架概述C. 群体系统的初始化D. 去中心化激光雷达-惯性状态估计 四. 实验A. 室内飞行B. 退化环境飞行C. 去中心化部署 五. 结论和未来工作 前言 原文&#xff1a;原文 准确的自我状态和相对状态估计是完成群体任务的关…

wsl 使用docker 部署oracle11g数据库

wsl 使用docker 部署oracle11g数据库 1. 下载oracle11g sudo docker pull registry.cn-hangzhou.aliyuncs.com/helowin/oracle_11g2. 运行oracle11g容器&#xff08;docker-compose&#xff09; services:oracle-1.0:container_name: oracle11gimage: oracle11g:1.0restart:…

IDEA集成JProfiler

目录 下载并安装JProfiler下载安装包管理员身份运行配置许可证邮箱复制注册码配置永久许可证选择IDE集成 在IDEA中下载并安装JProfiler插件启动并使用JProfiler进行性能分析启动Java应用程序&#xff1a;自动运行JProfiler 知识扩充功能 下载并安装JProfiler 下载安装包 官网…

Tomcat 和 Docker部署Java项目的区别

在 Java 项目部署中&#xff0c;Tomcat 和 Docker 是两种常见的选择。虽然它们都可以用来运行 Java 应用&#xff0c;但它们在定位、部署方式、依赖环境、资源隔离、扩展性和适用场景等方面有显著区别。 1. 功能定位 1.1 Tomcat Apache Tomcat 是一种轻量级的 Java 应用服务器…

AI-基本概念-多层感知器模型/CNN/RNN/自注意力模型

1 需求 神经网络 …… 深度学习 …… 深度学习包含哪些神经网络&#xff1a; 全连接神经网络卷积神经网络循环神经网络基于注意力机制的神经网络 2 接口 3 CNN 在这个示例中&#xff1a; 首先定义了一个简单的卷积神经网络SimpleCNN&#xff0c;它包含两个卷积层、两个池…

Leaflet查询矢量瓦片偏移的问题

1、问题现象 使用Leaflet绘制工具查询出来的结果有偏移 2、问题排查 1&#xff09;Leaflet中latLngToContainerPoint和latLngToLayerPoint的区别 2&#xff09;使用Leaflet查询需要使用像素坐标 3&#xff09;经排查发现&#xff0c;container获取的坐标是地图容器坐标&…

Vue生成名片二维码带logo并支持下载

一、需求 生成一张名片&#xff0c;名片上有用户信息以及二维码&#xff0c;名片支持下载功能&#xff08;背景样式可更换&#xff0c;忽略本文章样图样式&#xff09;。 二、参考文章 这不是我自己找官网自己摸索出来的&#xff0c;是借鉴各位前辈的&#xff0c;学以致用&am…

如何利用网站进行仿牌运营?

对于很多人来说&#xff0c;仿牌网站的运营是一项充满挑战的任务&#xff0c;很多初学者对如何开始感到困惑&#xff0c;甚至不清楚仿牌网站的运作机制。此外&#xff0c;搜索引擎对新网站的审核期也使得许多站长倍感压力。那么&#xff0c;如何才能在这一过程中有效地进行SEO优…

数字IC开发:布局布线

数字IC开发&#xff1a;布局布线 前端经过DFT&#xff0c;综合后输出网表文件给后端&#xff0c;由后端通过布局布线&#xff0c;将网表转换为GDSII文件&#xff1b;网表文件只包含单元器件及其连接等信息&#xff0c;GDS文件则包含其物理位置&#xff0c;具体的走线&#xff1…

传智杯 第六届-复赛-C

题目描述&#xff1a; 小红有一个数组&#xff0c;她每次可以选择数组的一个元素 xxx &#xff0c;将这个元素分成两个元素 aaa 和 bbb &#xff0c;使得 abxabxabx。请问小红最少需要操作多少次才可以使得数组的所有元素都相等。 输入描述: 第一行输入一个整数 n(1≤n≤10^5)…

华为配置 之 GVRP协议

目录 简介&#xff1a; 配置GVRP&#xff1a; 总结&#xff1a; 简介&#xff1a; GVRP&#xff08;GARP VLAN Registration Protocol&#xff09;&#xff0c;称为VLAN注册协议&#xff0c;是用来维护交换机中的VLAN动态注册信息&#xff0c;并传播该信息到其他交换机中&…

外包干了7天,技术明显退步。。。。。

先说一下自己的情况&#xff0c;本科生&#xff0c;22年通过校招进入南京某软件公司&#xff0c;干了接近2年的功能测试&#xff0c;今年年初&#xff0c;感觉自己不能够在这样下去了&#xff0c;长时间呆在一个舒适的环境会让一个人堕落!而我已经在一个企业干了2年的功能测试&…

openGauss开源数据库实战十

文章目录 任务十 openGauss逻辑结构:数据库管理任务目标实施步骤一、登录到openGauss二、创建数据库三、查看数据库集群中有哪些数据库四、查看数据库默认表空间的信息五、查看数据库下有哪些模式六、查看数据库下有哪些表七、修改数据库的默认表空间八、重命名数据库九、删除数…