当前位置: 首页 > news >正文

MuJoCo中的机器人状态获取

UR5e机器人xml文件模型

<mujoco model="ur5e"><compiler angle="radian" meshdir="assets" autolimits="true"/><option integrator="implicitfast"/><default><default class="ur5e"><material specular="0.5" shininess="0.25"/><joint axis="0 1 0" range="-6.28319 6.28319" armature="0.1"/><general gaintype="fixed" biastype="affine" ctrlrange="-6.2831 6.2831" gainprm="2000" biasprm="0 -2000 -400"forcerange="-150 150"/><default class="size3"><default class="size3_limited"><joint range="-3.1415 3.1415"/><general ctrlrange="-3.1415 3.1415"/></default></default><default class="size1"><general gainprm="500" biasprm="0 -500 -100" forcerange="-28 28"/></default><default class="visual"><geom type="mesh" contype="0" conaffinity="0" group="2"/></default><default class="collision"><geom type="capsule" group="3"/><default class="eef_collision"><geom type="cylinder"/></default></default><site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/></default></default><asset><material class="ur5e" name="black" rgba="0.033 0.033 0.033 1"/><material class="ur5e" name="jointgray" rgba="0.278 0.278 0.278 1"/><material class="ur5e" name="linkgray" rgba="0.82 0.82 0.82 1"/><material class="ur5e" name="urblue" rgba="0.49 0.678 0.8 1"/><mesh file="base_0.obj"/><mesh file="base_1.obj"/><mesh file="shoulder_0.obj"/><mesh file="shoulder_1.obj"/><mesh file="shoulder_2.obj"/><mesh file="upperarm_0.obj"/><mesh file="upperarm_1.obj"/><mesh file="upperarm_2.obj"/><mesh file="upperarm_3.obj"/><mesh file="forearm_0.obj"/><mesh file="forearm_1.obj"/><mesh file="forearm_2.obj"/><mesh file="forearm_3.obj"/><mesh file="wrist1_0.obj"/><mesh file="wrist1_1.obj"/><mesh file="wrist1_2.obj"/><mesh file="wrist2_0.obj"/><mesh file="wrist2_1.obj"/><mesh file="wrist2_2.obj"/><mesh file="wrist3.obj"/></asset><worldbody><light name="spotlight" mode="targetbodycom" target="wrist_2_link" pos="0 -1 2"/><body name="base" quat="1 0 0 0" childclass="ur5e"><inertial mass="4.0" pos="0 0 0" diaginertia="0.00443333156 0.00443333156 0.0072"/><geom mesh="base_0" material="black" class="visual"/><geom mesh="base_1" material="jointgray" class="visual"/><body name="shoulder_link" pos="0 0 0.163"><inertial mass="3.7" pos="0 0 0" diaginertia="0.0102675 0.0102675 0.00666"/><joint name="shoulder_pan_joint" class="size3" axis="0 0 1"/><geom mesh="shoulder_0" material="urblue" class="visual"/><geom mesh="shoulder_1" material="black" class="visual"/><geom mesh="shoulder_2" material="jointgray" class="visual"/><geom class="collision" size="0.06 0.06" pos="0 0 -0.04"/><body name="upper_arm_link" pos="0 0.138 0" quat="1 0 1 0"><inertial mass="8.393" pos="0 0 0.2125" diaginertia="0.133886 0.133886 0.0151074"/><joint name="shoulder_lift_joint" class="size3"/><geom mesh="upperarm_0" material="linkgray" class="visual"/><geom mesh="upperarm_1" material="black" class="visual"/><geom mesh="upperarm_2" material="jointgray" class="visual"/><geom mesh="upperarm_3" material="urblue" class="visual"/><geom class="collision" pos="0 -0.04 0" quat="1 1 0 0" size="0.06 0.06"/><geom class="collision" size="0.05 0.2" pos="0 0 0.2"/><body name="forearm_link" pos="0 -0.131 0.425"><inertial mass="2.275" pos="0 0 0.196" diaginertia="0.0311796 0.0311796 0.004095"/><joint name="elbow_joint" class="size3_limited"/><geom mesh="forearm_0" material="urblue" class="visual"/><geom mesh="forearm_1" material="linkgray" class="visual"/><geom mesh="forearm_2" material="black" class="visual"/><geom mesh="forearm_3" material="jointgray" class="visual"/><geom class="collision" pos="0 0.08 0" quat="1 1 0 0" size="0.055 0.06"/><geom class="collision" size="0.038 0.19" pos="0 0 0.2"/><body name="wrist_1_link" pos="0 0 0.392" quat="1 0 1 0"><inertial mass="1.219" pos="0 0.127 0" diaginertia="0.0025599 0.0025599 0.0021942"/><joint name="wrist_1_joint" class="size1"/><geom mesh="wrist1_0" material="black" class="visual"/><geom mesh="wrist1_1" material="urblue" class="visual"/><geom mesh="wrist1_2" material="jointgray" class="visual"/><geom class="collision" pos="0 0.05 0" quat="1 1 0 0" size="0.04 0.07"/><body name="wrist_2_link" pos="0 0.127 0"><inertial mass="1.219" pos="0 0 0.1" diaginertia="0.0025599 0.0025599 0.0021942"/><joint name="wrist_2_joint" axis="0 0 1" class="size1"/><geom mesh="wrist2_0" material="black" class="visual"/><geom mesh="wrist2_1" material="urblue" class="visual"/><geom mesh="wrist2_2" material="jointgray" class="visual"/><geom class="collision" size="0.04 0.06" pos="0 0 0.04"/><geom class="collision" pos="0 0.02 0.1" quat="1 1 0 0" size="0.04 0.04"/><body name="wrist_3_link" pos="0 0 0.1"><inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"diaginertia="0.000132134 9.90863e-05 9.90863e-05"/><joint name="wrist_3_joint" class="size1"/><geom material="linkgray" mesh="wrist3" class="visual"/><geom class="eef_collision" pos="0 0.08 0" quat="1 1 0 0" size="0.04 0.02"/><site name="attachment_site" pos="0 0.1 0" quat="-1 1 0 0"/></body></body></body></body></body></body></body></worldbody><sensor><force site="attachment_site" name="force_sensor"/><torque site="attachment_site" name="torque_sensor"/></sensor><actuator><general class="size3" name="shoulder_pan" joint="shoulder_pan_joint"/><general class="size3" name="shoulder_lift" joint="shoulder_lift_joint"/><general class="size3_limited" name="elbow" joint="elbow_joint"/><general class="size1" name="wrist_1" joint="wrist_1_joint"/><general class="size1" name="wrist_2" joint="wrist_2_joint"/><general class="size1" name="wrist_3" joint="wrist_3_joint"/></actuator><keyframe><key name="home" qpos="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0" ctrl="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0"/></keyframe>
</mujoco>

接触力

  <sensor><force site="attachment_site" name="force_sensor"/><torque site="attachment_site" name="torque_sensor"/></sensor>
## 获取末端受力和力矩force = data.sensor('force_sensor').datatorque = data.sensor('torque_sensor').data## 获取传感器的位置和旋转矩阵sensor_pos = data.site('attachment_site').xpossensor_mat = data.site('attachment_site').xmat.reshape(3, 3)## 将力转换到世界坐标系force_world = sensor_mat.dot(force)## 将力矩转换到世界坐标系torque_world = sensor_mat.dot(torque)## 合并力和力矩end_force = np.concatenate((force_world, torque_world), axis=0)## 计算feedback_forcefeedback_force = np.sqrt(np.sum(np.square(force_world)))

 <body name="wrist_3_link" pos="0 0 0.1"><inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"diaginertia="0.000132134 9.90863e-05 9.90863e-05"/><joint name="wrist_3_joint" class="size1"/><geom material="linkgray" mesh="wrist3" class="visual"/><geom class="eef_collision" pos="0 0.08 0" quat="1 1 0 0" size="0.04 0.02"/><site name="ee_site" pos="0 0.1 0" quat="-1 1 0 0"/></body>
 <actuator><general class="size3" name="shoulder_pan" joint="shoulder_pan_joint"/><general class="size3" name="shoulder_lift" joint="shoulder_lift_joint"/><general class="size3_limited" name="elbow" joint="elbow_joint"/><general class="size1" name="wrist_1" joint="wrist_1_joint"/><general class="size1" name="wrist_2" joint="wrist_2_joint"/><general class="size1" name="wrist_3" joint="wrist_3_joint"/></actuator>
def get_ee_pos(self):ee_site_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SITE, "ee_site")return self.data.site_xpos[ee_site_id].copy()def get_EE_POS_FROM_QPOS(self, qpos):self.data.qpos[:self.nq] = qpos[:self.nq]mujoco.mj_forward(self.model, self.data)ee_site_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SITE, "ee_site")return self.data.site_xpos[ee_site_id].copy()def get_EE_JACOBIAN(self):ee_site_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SITE, "ee_site")jacp = np.zeros((3, self.nv))jacr = np.zeros((3, self.nv))mujoco.mj_jacSite(self.model, self.data, jacp, jacr, ee_site_id)return jacpdef get_state(self):return np.concatenate([self.data.qpos[:self.nq], self.data.qvel[:self.nv]])def set_state(self, x):self.data.qpos[:self.nq] = x[:self.nq]self.data.qvel[:self.nv] = x[self.nq:]mujoco.mj_forward(self.model, self.data)def step(self, u):self.data.ctrl[:self.nu] = np.clip(u, -self.model.actuator_ctrlrange[:, 0], self.model.actuator_ctrlrange[:, 1])mujoco.mj_step(self.model, self.data)return self.get_state()
def get_ee_position(self):return self.data.xpos[self.wrist_3_body_id]def calculate_jacobian(self):jacp = np.zeros((3, self.model.nv))jacr = np.zeros((3, self.model.nv))mujoco.mj_jacBody(self.model, self.data, jacp, jacr, self.wrist_3_body_id)return jacp
# Get target joint positions using inverse kinematicsJ = self.calculate_jacobian()J_pinv = np.linalg.pinv(J)

    def get_pose(self):p = self.data.site_xpos[self.ee_site_idx].copy()    # posR = self.data.site_xmat[self.ee_site_idx].copy()    # rotation matrixreturn p, R.reshape((3,3))
 <site name="end_effector" type="sphere" size="0.005" pos="0.0 0 0.205" euler="0 0 0" rgba="1 0 0 1.00"/>
 <actuator><!-- Physical limits of the actuator. --><motor name="indy_joint0_actuator" joint="indy_joint1" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><motor name="indy_joint1_actuator" joint="indy_joint2" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><motor name="indy_joint2_actuator" joint="indy_joint3" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><motor name="indy_joint3_actuator" joint="indy_joint4" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><motor name="indy_joint4_actuator" joint="indy_joint5" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><motor name="indy_joint5_actuator" joint="indy_joint6" gear="1 0 0 0 0 0" ctrllimited="false" ctrlrange="-1e6 1e6" forcerange="-1e6 1e6"/><position ctrllimited="true" ctrlrange="-0.03 0" joint="jointf1" kp="2000" name="actf1"/><position ctrllimited="true" ctrlrange="0.0 0.03" joint="jointf2" kp="2000" name="actf2"/></actuator><sensor><framepos objtype="site" objname="end_effector"/><force name="force_sensor" site="end_effector"/><torque name="torque_sensor" site="end_effector"/></sensor>

def get_contact_force(mj_model, mj_data, body_name):bodyId = mujoco.mj_name2id(mj_model, MJ_BODY_OBJ, body_name)force_com = mj_data.cfrc_ext[bodyId, :]trn_force = force_com.copy()return np.hstack((trn_force[3:], trn_force[:3]))

 def get_ee_force(self,):sensor_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SENSOR, "force_sensor")# Get address and dimension of the sensoradr = self.model.sensor_adr[sensor_id]dim = self.model.sensor_dim[sensor_id]force = np.copy(self.data.sensordata[adr:adr + dim])# get torque sensor datasensor_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SENSOR, "torque_sensor")adr = self.model.sensor_adr[sensor_id]dim = self.model.sensor_dim[sensor_id]torque = np.copy(self.data.sensordata[adr:adr + dim])force_torque = np.concatenate([force, torque])# update robot stateft , dft = self.lp_filter_implemented(force_torque)return ft, dft
def get_ee_force_raw(self,):sensor_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SENSOR, "force_sensor")# Get address and dimension of the sensoradr = self.model.sensor_adr[sensor_id]dim = self.model.sensor_dim[sensor_id]force = np.copy(self.data.sensordata[adr:adr + dim])# get torque sensor datasensor_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SENSOR, "torque_sensor")adr = self.model.sensor_adr[sensor_id]dim = self.model.sensor_dim[sensor_id]torque = np.copy(self.data.sensordata[adr:adr + dim])force_torque = np.concatenate([force, torque])# force_sensor_data = self.lp_filter_raw(force_torque.reshape((-1, 6)))[0, :]ft_raw , dft_raw = self.lp_filter_implemented_raw(force_torque)return ft_raw , dft_raw
def transform_rot(self, fe, desired):pe, Re = self.get_pose()ps, Rs = desiredR12 = Rs.T @ ReMat = np.block([[R12, np.zeros((3, 3))], [np.zeros((3, 3)), R12]])return Mat.dot(fe)

状态获取

def get_jacobian(self):"""Get 6x7 geometric jacobian matrix."""dtype = self.data.qpos.dtypeN_full = self.model.nvjac = np.zeros((6, N_full), dtype=dtype)jac_pos = np.zeros((3 , N_full), dtype=dtype)jac_rot = np.zeros((3 , N_full), dtype=dtype)mujoco.mj_jacSite(self.model, self.data,jac_pos, jac_rot, self.ee_site_idx)jac[3:] = jac_rot.reshape((3, N_full))jac[:3] = jac_pos.reshape((3, N_full))# only return first 7 dofsreturn jac[:, :self.N].copy()def get_body_jacobian(self):Js = self.get_jacobian()p, R = self.get_pose()transform = np.block([[R.T, np.zeros((3,3))], [np.zeros((3,3)), R.T]])Jb = transform @ Jsreturn Jbdef get_body_ee_velocity(self):Jb = self.get_body_jacobian()dq = self.get_joint_velocity()[:self.N]Vb = Jb@dq.reshape((-1,1))return Vbdef get_spatial_ee_velocity(self):Js = self.get_jacobian()dq = self.get_joint_velocity()Vs = Js@dq.reshape((-1,1))return Vsdef get_joint_pose(self):return self.data.qpos.copy()def get_joint_velocity(self):return self.data.qvel.copy()def get_bias_torque(self):"""Get the gravity and Coriolis, centrifugal torque """return self.data.qfrc_bias[:self.N].copy()def get_full_inertia(self):M = np.zeros((self.model.nv, self.model.nv))mujoco.mj_fullM(self.model, M, self.data.qM)return M[:self.N, :self.N]def get_timestep(self):"""Timestep of the simulator is timestep of controller."""return self.model.opt.timestepdef get_sim_time(self):return self.data.time
def get_FT_value_raw(self):Fe, dFe = self.robot_state.get_ee_force_raw()return -Fedef get_eg(self, g, gd):p = g[:3,3]R = g[:3,:3]pd = gd[:3,3]Rd = gd[:3,:3]ep = R.T @ (p - pd)eR = vee_map(Rd.T @ R - R.T @ Rd).reshape((-1,))return np.hstack((ep, eR)).reshape((-1,1))
 Jb = self.robot_state.get_body_jacobian()# M,C,G = self.robot_state.get_dynamic_matrices()qfrc_bias = self.robot_state.get_bias_torque()M = self.robot_state.get_full_inertia()
def get_bias_torque(self):"""Get the gravity and Coriolis, centrifugal torque """return self.data.qfrc_bias[:self.N].copy()
qfrc_bias = self.robot_state.get_bias_torque()
tau_cmd = Jb.T @ tau_tilde + qfrc_bias.reshape((-1,1))

相关文章:

MuJoCo中的机器人状态获取

UR5e机器人xml文件模型 <mujoco model"ur5e"><compiler angle"radian" meshdir"assets" autolimits"true"/><option integrator"implicitfast"/><default><default class"ur5e">&…...

第五篇:linux之vim编辑器、用户相关

第五篇&#xff1a;linux之vim编辑器、用户相关 文章目录 第五篇&#xff1a;linux之vim编辑器、用户相关一、vim编辑器1、什么是vim&#xff1f;2、为什么要使用vim&#xff1f;3、vi和vim有什么区别&#xff1f;4、vim编辑器三种模式 二、用户相关1、什么是用户&#xff1f;2…...

taobao.trades.sold.get(淘宝店铺订单接口)

淘宝店铺提供了多种订单接口&#xff0c;可以用来获取订单信息、创建订单、修改订单等操作。 获取订单列表接口&#xff1a;可以使用该接口获取店铺的订单列表&#xff0c;包括订单号、买家信息、订单状态等。 获取单个订单信息接口&#xff1a;可以使用该接口获取指定订单的详…...

媒体发稿攻略,解锁新闻发稿成长新高度

新闻媒体发稿全攻略! 如何快速上稿主流权威央级媒体? 大家好!今天来聊聊媒体发稿的那些事儿&#xff0c;希望能帮到正在发稿或者准备发稿的小伙伴们。 ①明确目标媒体 首先&#xff0c;得搞清楚你要把稿子发给哪些媒体和。这一步非常关键&#xff0c;因为选择适合的媒体是发…...

WebRTC服务器Coturn服务器部署

1、概述 作为WebRTC服务器&#xff0c;只需要部署开源的coturn即可&#xff0c;coturn同时实现了STUN和TURN的协议 2、Coturn具体部署 2.1 Coturn简介 coturn是一个开源的STUN/TURN服务器&#xff0c;把STUN服务器跟TURN服务器都整合为一个服务器&#xff0c;主要提供一下几个功…...

lspci的资料

PCI即Peripheral Component Interconnect。 在 Linux 上使用 lspci 命令查看硬件情况 | Linux 中国 lspci 命令用于显示连接到 PCI 总线的所有设备&#xff0c;从而满足上述需求。该命令由 pciutils 包提供&#xff0c;可用于各种基于 Linux 和 BSD 的操作系统。 使用 lspci 和…...

GitLab 提交权限校验脚本

.git/hooks 目录详解与配置指南 一、什么是 .git/hooks&#xff1f; .git/hooks 是 Git 仓库中一个隐藏目录&#xff0c;用于存放 钩子脚本&#xff08;Hook Scripts&#xff09;。这些脚本会在 Git 执行特定操作&#xff08;如提交、推送、合并&#xff09;的前/后自动触发&…...

WebRTC服务器Coturn服务器相关测试工具

1、概述 在安装开源的webrtc服务器coturn服务器后&#xff0c;会附带安装coturn的相关工具&#xff0c;主要有以下几种工具 2、turnadmin工具 说明&#xff1a;服务器命令行工具&#xff0c;提供添加用户、添加管理员、生成TURN密钥等功能&#xff0c;turnadmin -h查看详细用…...

基于Python+Pytest实现自动化测试(全栈实战指南)

目录 第一篇&#xff1a;基础篇 第1章 自动化测试概述 1.1 什么是自动化测试 第2章 环境搭建与工具链配置 2.1 Python环境安装&#xff08;Windows/macOS/Linux&#xff09; 2.2 虚拟环境管理 2.3 Pytest基础配置&#xff08;pytest.ini&#xff09; 第3章 Pytest核心语…...

符号速率估计——小波变换法

[TOC]符号速率估计——小波变换法 一、原理 1.Haar小波变换 小波变换在信号处理领域被成为数学显微镜&#xff0c;不同于傅里叶变换&#xff0c;小波变换可以观测信号随时间变换的频谱特征&#xff0c;因此&#xff0c;常用于时频分析。   当小波变换前后位置处于同一个码元…...

SQLMesh隔离系统深度实践指南:动态模式映射与跨环境计算复用

在数据安全与开发效率的双重压力下&#xff0c;SQLMesh通过动态模式映射、跨环境计算复用和元数据隔离机制三大核心技术&#xff0c;完美解决了生产与非生产环境的数据壁垒问题。本文提供从环境配置到生产部署的完整实施框架&#xff0c;助您构建安全、高效、可扩展的数据工程体…...

调整IntelliJ IDEA中当前文件所在目录的显示位置

文章目录 1. 问题呈现2. 调整方法3. 更改后的界面 更多 IntelliJ IDEA 的使用技巧可查看 IntelliJ IDEA 专栏中的文章&#xff1a; IntelliJ IDEA 1. 问题呈现 在 IntelliJ IDEA 中&#xff0c;我们在浏览某个文件时&#xff0c;文件所在的目录会显示在下方的状态栏中&#x…...

关于ubuntu密码正确但是无法登录的情况

参考这个文章&#xff1a; https://blog.csdn.net/cuichongxin/article/details/117462494 检查一下是不是用户被lock了 输入passwd -s username 如果用户是L状态&#xff0c;那么就是lock了。 使用 passwd -u username 解锁 关于 .bashrc 不生效 有几点&#xff1a; ~/.…...

OpenCV中的透视变换方法详解

文章目录 引言1. 什么是透视变换2. 透视变换的数学原理3. OpenCV中的透视变换代码实现3.1 首先定义四个函数 3.1.1 cv_show() 函数 3.1.2 def resize() 函数 3.1.3 order_points() 函数 3.1.4 four_point_transform() 函数 3.2 读取图片并做预处理3.3 轮廓检测3.4 获取最大…...

基于DeepSeek的网络爬虫技术创新与实践应用

摘要 在人工智能迅猛发展的时代背景下&#xff0c;网络爬虫技术正经历着深刻变革。本文聚焦于融合DeepSeek大模型的开源爬虫框架Crawl4AI&#xff0c;深入探讨其在网络数据抓取与分析领域的技术原理、功能特性、应用实践及未来发展趋势。通过对Crawl4AI的异步操作、动态内容处理…...

Python基于语音识别的智能垃圾分类系统【附源码、文档说明】

博主介绍&#xff1a;✌Java老徐、7年大厂程序员经历。全网粉丝12w、csdn博客专家、掘金/华为云/阿里云/InfoQ等平台优质作者、专注于Java技术领域和毕业项目实战✌ &#x1f345;文末获取源码联系&#x1f345; &#x1f447;&#x1f3fb; 精彩专栏推荐订阅&#x1f447;&…...

关于RPC

1.什么是RPC RPC&#xff08;Remote Procedure Call&#xff09;&#xff0c;即远程过程调用&#xff08;协议&#xff09;。它允许像调用本地服务一样调用远程服务&#xff0c;用于实现分布式系统中跨网络进行通信 的技术&#xff0c;是一种计算机通信协议。 RPC是一种服务器…...

前端频繁调用后端接口问题思考

针对前端频繁调用后端接口的问题&#xff0c;以下是一套分步解决方案&#xff0c;结合Java后端技术栈&#xff1a; 1. 实时数据场景&#xff1a;WebSocket/SSE 适用场景&#xff1a;实时股票行情、即时聊天、监控仪表盘 // Spring WebSocket 配置示例 Configuration EnableW…...

Mujoco robosuite 机器人模型

import ctypes import os# 获取当前脚本所在的目录 script_dir os.path.dirname(os.path.abspath(__file__))# 构建库文件的相对路径 lib_relative_path os.path.join(dynamic_models, UR5e, Jb.so)# 拼接成完整的路径 lib_path os.path.join(script_dir, lib_relative_path…...

进阶篇 第 7 篇 (终章):融会贯通 - 多变量、模型选择与未来之路

进阶篇 第 7 篇 (终章)&#xff1a;融会贯通 - 多变量、模型选择与未来之路 (图片来源: Pixabay on Pexels) 我们已经一起走过了时间序列分析的进阶之旅&#xff01;从深入经典统计模型 ETS、ARIMA、SARIMA&#xff0c;到探索现代利器 Prophet&#xff0c;再到拥抱机器学习和初…...

网络安全·第五天·TCP协议安全分析

一、传输层协议概述 1、功能 传输层负责建立端到端的连接&#xff0c;即应用进程之间的通信&#xff0c;负责数据在端到端之间的传输。与网络层不同的是&#xff0c;网络层负责主机与主机之间的通信。 同时&#xff0c;传输层还要对收到的报文进行差错检测&#xff08;首部和…...

LX10-MDK的使用技巧

MDK5的使用技巧 查找匹配花括号 ​ Ctrle table键的妙用 一次右缩进4个(个人偏好设置)空格shiftenter取消,即左缩进 快速注释/取消注释 先选代码→ 快速编辑一列 按住ALT键选择一列编辑(实用性极强) 窗口拆分 倒数第一个:按列拆分倒数第二个:按行拆分 查找与替换(一个超级…...

IDEA创建Gradle项目然后删除报错解决方法

根据错误信息&#xff0c;你的项目目录中缺少Gradle构建必需的核心文件&#xff08;如settings.gradle/build.gradle&#xff09;&#xff0c;且IDEA可能残留了Gradle的配置。以下是具体解决方案&#xff1a; 一、问题根源分析 残留Gradle配置 你通过IDEA先创建了Gradle子模块…...

JavaScript性能优化实战(2):DOM操作优化策略

浏览器渲染原理与重排重绘机制 浏览器将HTML和CSS转换为用户可见页面的过程是前端开发的基础知识,也是理解DOM性能优化的关键。这个渲染过程大致可分为以下几个步骤: 渲染过程的核心步骤 解析HTML构建DOM树:浏览器解析HTML标记,转换为DOM树(Document Object Model),表…...

乐视系列玩机---乐视1s x500 x501 x502等系列线刷救砖以及刷写第三方twrp 卡刷第三方固件步骤解析

乐视乐1S(X500 x501 x502 等)采用联发科 Helio X10(MT6795T)Turbo 64位8核处理器 通过博文了解💝💝💝 1💝💝💝-----详细解析乐视1s x500 x501x502等系列黑砖线刷救砖的步骤 2💝💝💝----官方两种更新卡刷步骤以及刷写第三方twrp过程与资源 3💝💝…...

Spark-Streaming(1)

Spark Streaming概述&#xff1a; 用于流式计算&#xff0c;处理实时数据流。 数据流以DStream&#xff08;Discretized Stream&#xff09;形式表示&#xff0c;内部由一系列RDD组成。 Spark Streaming特点&#xff1a; 易用、容错、易整合到spark体系。 易用性&#xff1a…...

【Git】Git Revert 命令详解

Git Revert 命令详解 1. Git Revert 的基本概念 Git Revert 是一个用于撤销特定提交的命令。与 Git Reset 不同&#xff0c;Git Revert 不会更改提交历史&#xff0c;而是会创建一个新的提交来撤销指定提交的更改。这意味着&#xff0c;使用 Git Revert 后&#xff0c;项目的…...

SpringClound 微服务分布式Nacos学习笔记

一、基本概述 在实际项目中&#xff0c;选择哪种架构需要根据具体的需求、团队能力和技术栈等因素综合考虑。 单体架构&#xff08;Monolithic Architecture&#xff09; 单体架构是一种传统的软件架构风格&#xff0c;将整个应用程序构建为一个单一的、不可分割的单元。在这…...

PageIndex:构建无需切块向量化的 Agentic RAG

引言 你是否对长篇专业文档的向量数据库检索准确性感到失望&#xff1f;传统的基于向量的RAG系统依赖于语义相似性而非真正的相关性。但在检索中&#xff0c;我们真正需要的是相关性——这需要推理能力。当处理需要领域专业知识和多步推理的专业文档时&#xff0c;相似度搜索常…...

使用Java调用TensorFlow与PyTorch模型:DJL框架的应用探索

在现代机器学习的应用场景中&#xff0c;Python早已成为广泛使用的语言&#xff0c;尤其是在深度学习框架TensorFlow和PyTorch的开发和应用中。尽管Java在许多企业级应用中占据一席之地&#xff0c;但因为缺乏直接使用深度学习框架的能力&#xff0c;往往使得Java开发者对机器学…...

nodejs的包管理工具介绍,npm的介绍和安装,npm的初始化包 ,搜索包,下载安装包

nodejs的包管理工具介绍&#xff0c;npm的介绍和安装&#xff0c;npm的初始化包 &#xff0c;搜索包&#xff0c;下载安装包 &#x1f9f0; 一、Node.js 的包管理工具有哪些&#xff1f; 工具简介是否默认特点npmNode.js 官方的包管理工具&#xff08;Node Package Manager&am…...

LeetCode 热题 100_分割等和子集(89_416_中等_C++)(动态规划)

LeetCode 热题 100_分割等和子集&#xff08;89_416&#xff09; 题目描述&#xff1a;输入输出样例&#xff1a;题解&#xff1a;解题思路&#xff1a;思路一&#xff08;动态规划&#xff09;&#xff1a; 代码实现代码实现&#xff08;思路一&#xff08;动态规划&#xff0…...

EasyCVR视频智能分析平台助力智慧园区:全场景视频监控摄像头融合解决方案

一、方案背景 在智慧园区建设的浪潮下&#xff0c;设备融合、数据整合与智能联动已成为核心诉求。视频监控作为智慧园区的“视觉中枢”&#xff0c;其高效整合直接影响园区的管理效能与安全水平。然而&#xff0c;园区内繁杂的视频监控设备生态——不同品牌、型号、制式的摄像…...

《剥开卷积神经网络CNN的 “千层酥”:从基础架构到核心算法》

文章目录 前言卷积神经网络&#xff08;Convolutional Neural Network&#xff0c;CNN&#xff09;是一种专门用于处理网格结构数据&#xff08;如图像、视频、音频&#xff09;的深度学习模型。它在计算机视觉任务&#xff08;如图像分类、目标检测&#xff09;中表现尤为出色…...

win10中打开python的交互模式

不是输入python3&#xff0c;输入python&#xff0c;不知道和安装python版本有没有关系。做个简单记录&#xff0c;不想记笔记了...

技术与情感交织的一生 (七)

目录 出师 大三 MVP 首战 TYMIS はじめまして 辣子鸡丁 报价 日本人 致命失误 大佬 包围 品质保障 扩军 唯快不破 闪电战 毕业 总攻 Hold On 出师 大三 大三的学习生活&#xff0c;能认认真真的上一天课的时候很少&#xff0c;甚至经常因为客户的 “传呼”…...

ElasticSearch深入解析(一):Elastic Stack全景

一、Elastic Stack的发展 过去和现在&#xff1a; Elastic数据平台在搜索、地理位置、内部日志、数据指标、安全监控和APM应用性能管理等场景中的应用颇具亮点。 APM&#xff08;Application Performance Management&#xff0c;应用性能管理&#xff09;是一种用于监控和管理…...

CAD在线查看免费,可以支持DWG/GLB/GLTF/doc/wps/pdf/psd/eml/zip, rar/MP3/MP4/svg/OBJ/FBX格式

CAD在线查看免费&#xff0c;可以支持DWG/GLB/GLTF/doc/wps/pdf/psd/eml/zip, rar/MP3/MP4/svg/OBJ/FBX格式 m.gszh.xyz m.gszh.xyz 免费支持以下格式文件在线查看类型 支持 doc, docx, xls, xlsx, xlsm, ppt, pptx, csv, tsv, dotm, xlt, xltm, dot, dotx, xlam, xla, pages …...

【机器学习案列-21】基于 LightGBM 的智能手机用户行为分类

&#x1f9d1; 博主简介&#xff1a;曾任某智慧城市类企业算法总监&#xff0c;目前在美国市场的物流公司从事高级算法工程师一职&#xff0c;深耕人工智能领域&#xff0c;精通python数据挖掘、可视化、机器学习等&#xff0c;发表过AI相关的专利并多次在AI类比赛中获奖。CSDN…...

多路转接poll服务器

目录 函数原型 poll服务器 对比select的优点 关于select的详解&#xff0c;可查看多路转接select服务器-CSDN博客 函数原型 #include <poll.h> int poll(struct pollfd *fds, nfds_t nfds, int timeout); poll作为多路转接的实现方案&#xff0c;与select要解决的问…...

全本地化智能数字人

&#x1f31f;EdgePersona- 全本地化智能数字人 ​完全离线 | 隐私无忧 | 轻量高效 |笔记本友好 测试效果&#xff1a;【纯本地部署的电子魅魔&#xff01;笔记本也能离线&#xff0c;隐私性拉满】 https://www.bilibili.com/video/BV1jydeYTETD/?share_sourcecopy_web&v…...

第6次课 贪心算法 A

向日葵朝着太阳转动&#xff0c;时刻追求自身成长的最大可能。 贪心策略在一轮轮的简单选择中&#xff0c;逐步导向最佳答案。 课堂学习 引入 贪心算法&#xff08;英语&#xff1a;greedy algorithm&#xff09;&#xff0c;是用计算机来模拟一个「贪心」的人做出决策的过程…...

Docker 部署 PostgreSQL 数据库

Docker 部署 PostgreSQL 数据库 基于 Docker 部署 PostgreSQL 数据库一、拉取 PostgreSQL 镜像二、运行 PostgreSQL 容器三、运行命令参数详解四、查看容器运行状态 基于 Docker 部署 PostgreSQL 数据库 一、拉取 PostgreSQL 镜像 首先&#xff0c;确保你的 Docker 环境已正确…...

Android如何通过aspectj打造一个无侵入式动态权限申请框架

目录 一,背景 二,通过Aspectj管理所有的注解 三,配置注解 四,通过空白Activity完成真正的权限申请 五,引入依赖配置 一,背景 在Activity或者fragment中&#xff0c;写在几个方法写一些注释&#xff0c;用来表示权限申请成功&#xff0c;申请失败&#xff0c;多次拒绝。…...

Flink介绍——实时计算核心论文之Dataflow论文详解

引入 在过去的几篇文章里&#xff0c;我们看到了大数据的流式处理系统是如何一步一步进化的。从最早出现的S4&#xff0c;到能够做到“至少一次”处理的Storm&#xff0c;最后是能够做到“正好一次”数据处理的MillWheel。我们会发现&#xff0c;这些流式处理框架&#xff0c;…...

浅克隆(--depth 1)后如何获取完整的历史记录

如果远程remote为origin&#xff0c;则origin可以不写&#xff0c;如不是&#xff0c;则必须要写 获取全部分支 git fetch origin refs/heads/*:refs/remotes/origin/* 单独获取master分支 git fetch origin refs/heads/master:refs/remotes/origin/master 获取全部历史…...

安宝特案例 | 某知名日系汽车制造厂,借助AR实现智慧化转型

案例介绍 在全球制造业加速数字化的背景下&#xff0c;工厂的生产管理与设备维护效率愈发重要。 某知名日系汽车制造厂当前面临着设备的实时监控、故障维护&#xff0c;以及跨地域的管理协作等挑战&#xff0c;由于场地分散和突发状况的不可预知性&#xff0c;传统方式已无法…...

Feign 深度解析:Java 声明式 HTTP 客户端的终极指南

Feign 深度解析&#xff1a;Java 声明式 HTTP 客户端的终极指南 Feign 是由 Netflix 开源的 ​声明式 HTTP 客户端&#xff0c;后成为 Spring Cloud 生态的核心组件&#xff08;现由 OpenFeign 维护&#xff09;。它通过注解和接口定义简化了服务间 RESTful 通信&#xff0c;并…...

WPS Office安卓版云文档同步速度与PDF转换体验测评

WPS Office安卓版是很多人常用的移动办公软件。它支持在线编辑、文档同步、格式转换等功能&#xff0c;适合手机和平板用户随时处理文档。我们用它配合谷歌浏览器打开网页文档时&#xff0c;也可以将内容快速保存到云端或转换成PDF格式使用。 先说云文档同步。在打开WPS Office…...

ARM汇编的LDM和STM指令

批量加载/存储指令可以实现在一组寄存器和一块连续的内存单元之间传输数据.LDM 为加载多个寄存器&#xff0c;STM 为存储多个寄存器.允许一条指令传送 16 个寄存器的任何子集或所有寄存器.指令格式如下: LDM{cond}<模式> Rn{!},reglist{^} STM{cond}<模式> Rn{!}…...