【代码讲解】SO-ARM100 双场景演示:手柄驱动 Mujoco 仿真 + 实机控制

视频讲解:

【代码讲解】SO-ARM100 双场景演示:手柄驱动 Mujoco 仿真 + 实机控制

今天介绍下使用使用北通手柄通过控制 Mujoco 中的 SO-ARM100 机械臂,然后将关节数据通过 zmq 通信转发控制实际机械臂。

本期中会涉及如下点,需要注意:

  1. 末端姿态设置为固定姿态,但控制量可以进行修改,目前手柄没有想好用哪些键映射比较好
  2. 机械臂会严格按照 Mujoco 的 qpos 进行执行,所以最好做限位等关节处理做保护,这部分我在 SO-ARM100 的被控代码中增加了,大家自己写这部分的时候需要注意

完整代码仓库:

https://github.com/LitchiCheng/mujoco-learning

https://github.com/LitchiCheng/SO-ARM100

Joystick 接收 和 Mujoco 仿真转发端

import mujoco
import numpy as np
import mujoco_viewer
import casadi_ik
import time
import pygame
import os
import math
from so100_real_control import ZMQCommunicator# 设置环境变量以确保正确访问游戏杆设备
os.environ["SDL_JOYSTICK_DEVICE"] = "/dev/input/js0"
SCENE_XML_PATH = 'model/trs_so_arm100/scene.xml'
ARM_XML_PATH = 'model/trs_so_arm100/so_arm100.xml'class XboxController:"""Xbox手柄控制器类,负责处理所有手柄输入"""def __init__(self):# 初始化位置参数self.x = 0.0self.y = -0.3self.z = 0.15# 位置限制self.x_min, self.x_max = -0.3, 0.3self.y_min, self.y_max = -0.4, 0.0self.z_min, self.z_max = 0.05, 0.3# 控制灵敏度self.sensitivity = 0.005# 死区阈值(过滤摇杆中心微小漂移)self.deadzone = 0.1self.dof5_target = Noneself.button1_pressed = Falseself.button2_pressed = Falseself.controller = self.init_controller()def init_controller(self):"""初始化Xbox手柄(通过pygame访问js设备)"""pygame.init()pygame.joystick.init()if pygame.joystick.get_count() == 0:print("joystick not found")return None# 对应/dev/input/js0joystick = pygame.joystick.Joystick(0)joystick.init()print(f"joystick found: {joystick.get_name()}")print(f"button count: {joystick.get_numbuttons()}")return joystickdef is_connected(self):"""检查手柄是否连接"""return self.controller is not Nonedef handle_input(self, arm):"""处理手柄输入并更新控制参数"""if not self.is_connected():return# 处理pygame事件(必须调用,否则无法更新轴值和按钮状态)pygame.event.pump()# 读取左摇杆X轴(0号轴)x_axis = self.controller.get_axis(1)# 应用死区过滤if abs(x_axis) < self.deadzone:x_axis = 0.0# 读取左摇杆Y轴(1号轴)y_axis = self.controller.get_axis(0)if abs(y_axis) < self.deadzone:y_axis = 0.0# 读取右摇杆Y轴(4号轴)z_axis = -self.controller.get_axis(4)if abs(z_axis) < self.deadzone:z_axis = 0.0# 根据轴值更新位置self.x = np.clip(self.x + x_axis * self.sensitivity, self.x_min, self.x_max)self.y = np.clip(self.y + y_axis * self.sensitivity, self.y_min, self.y_max)self.z = np.clip(self.z + z_axis * self.sensitivity, self.z_min, self.z_max)# 检测按钮1(假设是0号按钮,通常是A键)button1 = self.controller.get_button(0)if button1 and not self.button1_pressed:print("Button1 pressed - 设置dof[5]为满量程")self.dof5_target = arm.model.upperPositionLimit[5]self.button1_pressed = Trueelif not button1:self.button1_pressed = False# 检测按钮2(假设是1号按钮,通常是B键)button2 = self.controller.get_button(1)if button2 and not self.button2_pressed:print("Button2 pressed - 设置dof[5]为最小值")self.dof5_target = arm.model.lowerPositionLimit[5]self.button2_pressed = Trueelif not button2:self.button2_pressed = Falsedef get_position_target(self):return self.x, self.y, self.zdef get_dof5_target(self):return self.dof5_targetdef cleanup(self):pygame.quit()class RobotController(mujoco_viewer.CustomViewer):    def __init__(self, scene_path, arm_path, controller):super().__init__(scene_path, distance=1.5, azimuth=135, elevation=-30)self.scene_path = scene_pathself.arm_path = arm_pathself.controller = controllerself.communicator = ZMQCommunicator()self.arm = casadi_ik.Kinematics("Wrist_Roll")self.arm.buildFromMJCF(arm_path)self.last_dof = Nonedef runBefore(self):passdef runFunc(self):"""主循环中执行的函数"""self.controller.handle_input(self.arm)x, y, z = self.controller.get_position_target()print(f"当前位置: x={x:.3f}, y={y:.3f}, z={z:.3f}")# 构建变换矩阵(保持末端执行器姿态不变)tf = self.build_transform_simple(x, y, z, np.pi / 4, 0, 0)self.dof, info = self.arm.ik(tf, current_arm_motor_q=self.last_dof)self.last_dof = self.dofdof5_target = self.controller.get_dof5_target()if dof5_target is not None:self.dof[5] = dof5_targetself.data.qpos[:6] = self.dof[:6]sim_joint_rad = self.data.qpos[:6].copy()sim_joint_deg = [math.degrees(q) for q in sim_joint_rad]self.communicator.send_data(sim_joint_deg)mujoco.mj_step(self.model, self.data)time.sleep(0.01)def build_transform_simple(self, x, y, z, roll, pitch, yaw):cr, sr = np.cos(roll), np.sin(roll)cp, sp = np.cos(pitch), np.sin(pitch)cy, sy = np.cos(yaw), np.sin(yaw)return np.array([[cy*cp, cy*sp*sr - sy*cr, cy*sp*cr + sy*sr, x],[sy*cp, sy*sp*sr + cy*cr, sy*sp*cr - cy*sr, y],[-sp,   cp*sr,            cp*cr,            z],[0,     0,                0,                1]])if __name__ == "__main__":controller = XboxController()if not controller.is_connected():print("joystick not connected")exit(1)try:robot = RobotController(SCENE_XML_PATH, ARM_XML_PATH, controller)robot.run_loop()finally:controller.cleanup()

SO-ARM100 实机控制端

import zmq
import json
import sys
import os
project_root = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
sys.path.insert(0, project_root)
from hardware import FeetechMotor as fmimport time# 初始化机械臂
motor = fm.FeetechMotor(1, "/dev/ttyACM0")
motor.connect()# # ZMQ配置
# ZMQ_IP = "127.0.0.1"
# ZMQ_PORT = "5555"
# context = zmq.Context()
# socket = context.socket(zmq.SUB)
# socket.connect(f"tcp://{ZMQ_IP}:{ZMQ_PORT}")
# # 订阅所有消息(空字符串表示订阅所有主题)
# socket.setsockopt_string(zmq.SUBSCRIBE, "")# print(f"等待仿真端发布数据... 连接到:tcp://{ZMQ_IP}:{ZMQ_PORT}")# ZMQ IPC配置 - 使用进程间通信协议
ZMQ_IPC_PATH = "ipc:///tmp/robot_arm_comm.ipc"  # 与发布者相同的IPC路径
context = zmq.Context()
socket = context.socket(zmq.SUB)
socket.connect(ZMQ_IPC_PATH)  # 连接到IPC路径
socket.setsockopt_string(zmq.SUBSCRIBE, "")  # 订阅所有消息print(f"控制端订阅者启动,连接到:{ZMQ_IPC_PATH}")# 接收并解析数据
try:while True:# 接收数据data = socket.recv_string().strip()if not data:continue# 解析JSON数据json_data = json.loads(data)joint_pos_deg = json_data["joint_pos"]control_mode = json_data["control_mode"]# 发送控制指令给实际机械臂if control_mode == "position":for i in range(1, 7):motor.setMotorId(i)motor.setSpeed(2000)  # 设置目标速度为1000步/秒motor.printFlag(False)  # 打开打印if i == 1 or i == 2:motor.setPID(16, 16, 0)else:   motor.setPID(32, 32, 0)  # 设置PID参数motor.setPosition(joint_pos_deg[i - 1])# print(f"Motor ID {i} set to position {joint_pos_deg[i - 1]}°")# 短暂延迟,避免CPU占用过高# time.sleep(0.01)except KeyboardInterrupt:print("程序被用户中断")
except Exception as e:print(f"接收/控制错误:{e}")
finally:# 关闭连接与机械臂socket.close()context.term()motor.disconnect()

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

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

相关文章

「数据获取」《中国教育经费统计年鉴》(1997-2024)

01、数据简介《中国教育经费统计年鉴》作为我国教育经费领域的核心统计典籍&#xff0c;全面系统地呈现了全国各级各类教育经费的来源构成、分配流向与使用成效。其统计范围覆盖学前教育、基础教育、中等职业教育、高等教育及特殊教育等全学段&#xff0c;数据维度涵盖财政性教…

使用 Logspout 收集所有容器的

1.将所有容器的输出路由到远程 rsyslog 服务器1.修改 rsyslog 配置文件/etc/rsyslog.conf, 从中找到 “# Provides UDP sysilog recepion"语句。并将该处的以下两行配置代码行首的“#”字符删除&#xff08;取消注释&#xff09;[roothost1 ~]# vi /etc/rsyslog.conf [roo…

【智能化解决方案】基于多目标优化检索增强生成的智能行程规划方案

&#x1f4dd; 基于多目标优化的智能行程规划方案 1 用户需求分析与矩阵构建 1.1 核心用户信息提取 根据用户提供的年龄、出发地、目的地、出行时间等基本信息&#xff0c;我们首先构建一个用户特征向量&#xff1a; U {Age, Origin, Destination, TravelDate, Duration, Budg…

软件研发的演变

软件研发从一门手工作坊式的艺术&#xff0c;逐步演进为一门系统化、工程化、智能化的现代学科。其发展历程不仅体现了技术的飞跃&#xff0c;更反映了方法论、协作模式和思维方式的深刻变革。一、发展演变历程软件研发的演变可以大致划分为以下几个阶段&#xff1a;1. 软件作坊…

「日拱一码」091 机器学习——集成学习

目录 集成学习介绍 1. 核心思想 2. 为什么有效&#xff1f; 3. 主要流派与方法 A. 并行方法&#xff1a;Bagging (Bootstrap Aggregating) B. 串行方法&#xff1a;Boosting C. 堆叠法&#xff1a;Stacking 代码示例 Bagging 的代表 —— 随机森林 (Random Forest) 集成…

vscode实现第三方包的使用,cmake结合vcpkg(跨平台)

要使用cmake和vcpkg组织一个完整的现代cpp项目&#xff0c;一般来说需要三个文件vcpkg.json描述第三方依赖项//vcpkg.json {"dependencies": ["fmt"] }//安装,在vcpkg.json目录执行 vcpkg installCMakePresets.json定义项目的本质属性&#xff08;What&…

DevExpress中Word Processing Document API学习记录

文章目录1 文档结构划分2 文档操作基础2.1 Positions and Ranges2.2 Secitions2.3 Paragraphs2.4 Tables2.5 Lists2.6 Hyperlinks and Bookmarks2.7 Comments2.8 Headers and Footers2.9 Shapes and Pictures2.10 Watermarks2.11 Charts2.12 OLE Objects2.13 ActiveX Controls2…

Roo Code 的差异_快速编辑功能

什么是差异编辑&#xff1f; 简单来说&#xff0c;差异编辑就像是一位细心的装修师傅&#xff1a;他不会把整个房子拆掉重盖&#xff0c;而是精准地只修补需要改动的部分。Roo Code 的这项功能默认开启&#xff0c;它通过比对代码差异&#xff08;diff&#xff09;来实施修改&a…

【Axure高保真原型】标签树分类查询案例

今天和大家分享标签树分类查询案例的原型模版&#xff0c;效果包括&#xff1a; 树形分类——点击左侧树形里的箭头&#xff0c;可以展开或收起子级选项&#xff1b; 查询表格——点击标签树里的选项&#xff0c;如果是末级选项&#xff0c;可以筛选右侧表格用户标签&#xf…

容器化部署项目05

一、工作原理 镜像&#xff1a;容器的模板&#xff0c;包括容器运行时所需的数据 容器&#xff1a;运行中的进程&#xff0c;依赖镜像运行&#xff0c;镜像的具现化 镜像你可以把它看成Python中的类&#xff0c;而容器可以看做是类的实例化对象。 一个类可以有多个对象&#xf…

微信小程序 工作日历 周计划日报 修改等提报和状态展示功能,支持h5,Android ,ios,基于uniapp,适配vue2和vue3

Work-calendar 介绍 &#xff08;底部附链接&#xff09; 基于uni-calendar做的定制化开发&#xff0c;主要功能为工作日历展示和提报组件 ​ 1.支持周计划日报状态展示且可配置 ​ 2.支持农历展示配置&#xff0c;回到当日&#xff0c;月份切换 ​ 3.日历&#xff0c;周报…

openharmony 鸿蒙 下 利用蓝牙API(a2dp模块-高级音频,ble模块-低功耗蓝牙等)完成对蓝牙音响的控制(蓝牙广播)

1.首先是登录页面&#xff08;利用webapi 和本地数据存储完成登陆操作&#xff09; 2.添加设备&#xff08;利用ble.startBLEScan 和 ble.on("BLEDeviceFind", onReceiveEvent);完成蓝牙扫描与显示&#xff09; 3.蓝牙ble连接&#xff08;利用ble.createGattClientDe…

17、逻辑回归与分类评估 - 从连续到离散的智能判断

学习目标:理解分类问题的本质和评估方法,掌握逻辑回归的数学原理和概率解释,学会二分类和多分类问题的处理方法,熟练使用分类评估指标,理解过拟合和正则化的基本概念。 > 从第16章到第17章:从预测数值到判断类别 在第16章中,我们学习了线性回归,解决的是预测连续数…

自动化脚本的核心引擎

自动化脚本作为现代软件开发与运维的重要工具&#xff0c;其核心引擎承担着解析指令、调度任务和执行逻辑的关键职能。这种引擎本质上是一个轻量级的运行时环境&#xff0c;通过预定义的规则集将人类可读的脚本语言转化为机器可执行的原子操作。在持续集成/持续交付&#xff08…

【Vue2 ✨】Vue2 入门之旅 · 进阶篇(九):Vue2 性能优化

在前几篇文章中&#xff0c;我们学习了 Vuex 的内部机制以及 Vue Router 的工作原理。本篇将深入探讨 Vue2 性能优化&#xff0c;帮助你掌握在开发中提升 Vue 应用性能的方法和技巧。 目录 性能优化的意义响应式系统优化虚拟 DOM 与渲染优化组件懒加载与按需渲染事件与计算属性…

【题解】B2600 【深基1.例2】简单的分苹果

题目描述 这里有 101010 个苹果&#xff0c;小 A 拿走了 222 个&#xff0c;Uim 拿走了 444 个&#xff0c;八尾勇拿走剩下的所有的苹果。我们想知道&#xff1a; 小A 和 Uim 两个人一共拿走多少苹果&#xff1f;八尾勇能拿走多少苹果&#xff1f; 现在需要编写一个程序&#x…

中小企业 4G 专网部署:性能与成本的最佳平衡

在数字化转型的浪潮中&#xff0c;中小企业同样需要安全、稳定和高效的通信网络。然而&#xff0c;传统专网的高成本和复杂部署往往成为阻碍。IPLOOK 提供的4G轻量级核心网与专网解决方案&#xff0c;正是帮助中小企业在性能与成本之间找到最佳平衡的关键。 中小企业的网络挑…

LeetCode每日一题,20250914

元音拼写检查器 思路 精确匹配 用 HashSet 保存原始单词&#xff0c;查询时直接判断是否存在。 大小写忽略匹配 用 HashMap<String, String> 保存 小写单词 -> 第一次出现的原始单词。用 putIfAbsent&#xff0c;确保只记录第一次出现的单词。 元音模糊匹配 把单词…

i2s_record_play

这章主要讲述i2s 1&#xff1a;环境及配件 esp32c3 esp32s3 idf5.4.1 INMP441 MAX98357A 都使用dma 2&#xff1a;eps32c3 测试 只有1个i2s 只能一边录 完 再播放 &#xff0c;内存太小&#xff0c;这里用 flash 存audio里 只说能 录音 能播放 &#xff0c;效果不好&#xff0…

Spring Boot 3 + EasyExcel 文件导入导出实现

SpringBoot集成EasyExcel 3.x&#xff1a;高效实现Excel数据的优雅导入与导出 在现代企业应用中&#xff0c;Excel作为数据交换的重要工具&#xff0c;几乎无处不在。如何高效且优雅地实现Excel数据的导入与导出&#xff0c;是每个开发者都需要面对的问题。EasyExcel是阿里巴巴…