灵心巧手,创造万物。
LinkerHand 灵巧手 ROS SDK 是由灵心巧手(北京)科技有限公司开发的一款软件工具,用于驱动其灵巧手系列产品,并提供功能示例。它支持多种设备(如笔记本、台式机、树莓派、Jetson 等),主要服务于人型机器人、工业自动化和科研院所等领域,适用于人型机器人、柔性化生产线、具身大模型训练和数据采集等场景。
警告
请保持远离灵巧手活动范围,避免造成人身伤害或设备损坏。
执行动作前请务必进行安全评估,以防止发生碰撞。
请保护好灵巧手。
| Name | Version | Link |
|---|---|---|
| Python SDK | ||
| ROS SDK | ||
| ROS2 SDK |
V3.0.1
V2.2.4
v2.2.3
V2.1.9
V2.1.8
操作系统:Ubuntu20.04
ROS版本:Noetic
Python版本:V3.8.10
硬件接口:5v标准USB接口
$ mkdir -p Linker_Hand_SDK_ROS/src #创建目录
$ cd Linker_Hand_SDK_ROS/src #进入目录
$ git clone https://github.com/linker-bot/linkerhand-ros-sdk.git #获取SDK
$ sudo apt install python3-can
$ cd Linker_Hand_SDK_ROS/src/linker_hand_sdk #进入目录
$ pip install -r requirements.txt #安装所需依赖
$ cd Linker_Hand_SDK_ROS # 回到工程目录
$ catkin_make #编译和构建ROS包
支持分布式计算和模块化开发,只在本终端生效,如不需要则忽略。树莓派设备已默认配置完成。
$ source /opt/ros/noetic/setup.bash
$ export ROS_MASTER_URI=http://<ROS Master IP>:11311
$ export ROS_IP=<本机IP>
$ export ROS_HOSTNAME=<本机IP>
无论是真机运行还是仿真模拟,均需要先修改配置参数文件。
目前,ROS开发的图形界面控制示例,只能单独控制一只LinkerHand灵巧手。
$ cd Linker_Hand_SDK_ROS/src/linker_hand_sdk/linker_hand_sdk_ros/scripts/LinkerHand/config
$ sudo vim setting.yaml #编辑配置文件
setting.yaml描述
VERSION: 2.0.2 # 重构核心源码,支持动捕手套速度
LINKER_HAND: # 手部配置信息
LEFT_HAND:
EXISTS: True # 是否存在左手,如果不存在,请修改为False
TOUCH: True # 是否有压力传感器,如果不存在,请修改为False
JOINT: L7 # 左手关节数 L7 \ L10 \ L20 \ L25
NAME: # 无论l10还是l20 joint name都是20个
- joint41
- joint42
- joint43
- joint44
- joint45
- joint46
- joint47
- joint48
- joint49
- joint50
- joint51
- joint52
- joint53
- joint54
- joint55
- joint56
- joint57
- joint58
- joint59
- joint60
RIGHT_HAND:
EXISTS: False # 是否存在右手
TOUCH: True # 是否有压力传感器
JOINT: L10 # 右手关节数量 L7 \ L10 \ L20 \ L25
NAME: # 无论l10还是l20 joint name都是20个
- joint71
- joint72
- joint73
- joint77
- joint75
- joint76
- joint77
- joint78
- joint79
- joint80
- joint81
- joint82
- joint83
- joint84
- joint88
- joint86
- joint87
- joint88
- joint89
- joint90
PASSWORD: "12345678" # 由于与can通讯,需要激活通讯接口用到系统管理员密码
修改launch文件进行参数配置
$ cd /Linker_Hand_SDK_ROS/src/linker_hand_sdk_ros/launch/
$ sudo vim linker_hand.launch #启动左or右单手,按照注释编辑配置文件
$ sudo vim linker_hand_double.launch #启动左右双手,按照注释编辑配置文件
# 如果报错
ERROR: cannot launch node of type [linker_hand_sdk_ros/linker_hand.py]: Cannot locate node of type [linker_hand.py] in package [linker_hand_sdk_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
# 需要给执行文件权限
$ sudo chmod a+x src/linkerhand-ros-sdk/linker_hand_sdk_ros/scripts/linker_hand.py
# 然后在执行
$ sudo vim linker_hand.launch #启动左or右单手,按照注释编辑配置文件
$ sudo vim linker_hand_double.launch #启动左右双手,按照注释编辑配置文
<?xml version="1.0" encoding="utf-8"?>
<launch>
<node pkg="linker_hand_sdk_ros" type="linker_hand.py" name="linker_hand_sdk" output="screen" > <!-- 启动SDK -->
<param name="hand_type" type="string" value="right"/> <!--left or right-->
<param name="hand_joint" type="string" value="L10"/> <!--L7 | L10 | L20 | L21 | L25-->
<param name="touch" type="bool" value="true"/> <!--是否有压力传感器-->
</node>
</launch>
<arg name="left_hand_joint" default="L10"/> <!-- 左手型号 L20 | L21 | L25-->
<arg name="right_hand_joint" default="L10"/> <!-- 右手型号 L20 | L21 | L25-->
<arg name="left_touch" default="true"/> <!-- 左手压力传感器 true or false-->
<arg name="right_touch" default="true"/> <!-- 右手压力传感器 true or false-->
<arg name="left_can" default="can0"/> <!-- 左手USB转CAN编号 can0-->
<arg name="right_can" default="can0"/> <!-- 右手USB转CAN编号 can0-->
<arg name="left_hand_joint" default="L10"/> <!-- 左手型号 L7 | L10 | L20 | L21 | L25-->
<arg name="right_hand_joint" default="L10"/> <!-- 右手型号 L7 | L10 | L20 | L21 | L25-->
<arg name="left_touch" default="true"/> <!-- 左手压力传感器 true or false-->
<arg name="right_touch" default="true"/> <!-- 右手压力传感器 true or false-->
<arg name="left_can" default="can0"/> <!-- 左手USB转CAN编号 can0-->
<arg name="right_can" default="can1"/> <!-- 右手USB转CAN编号 can0-->
灯光闪烁:蓝色灯闪烁代表通讯成功。
通讯模式:如何通过CAN模块连接的时候,区分是CAN还是485? CAN接口和485接口完全不同。连接方式也不同
启动LinkerHand L10、L20灵巧手SDK,启动成功后会有SDK版本、CAN接口状态、灵巧手配置信息和当前灵巧手关节速度等提示信息。
# 开启CAN端口
$ sudo /usr/sbin/ip link set can0 up type can bitrate 1000000 #USB转CAN设备蓝色灯常亮状态 在按照要求修改setting.ymal配置文件后,Ubuntu系统可以不做此步
$ cd ~/Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch #左or右单手启动
or
$ roslaunch linker_hand_sdk_ros linker_hand_double.launch #启动左右双手
# 如果报错
ERROR: cannot launch node of type [linker_hand_sdk_ros/linker_hand.py]: Cannot locate node of type [linker_hand.py] in package [linker_hand_sdk_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
# 需要给执行文件权限
$ sudo chmod a+x src/linker_hand_sdk/linker_hand_sdk_ros/scripts/linker_hand.py
$ roslaunch linker_hand_sdk_ros linker_hand.launch
编辑scripts/LinkerHand/config/setting.yaml配置文件,按照配置文件内注释说明进行参数修改,将MODBUS:"/dev/ttyUSB0",并且linker_hand.launch.py配置文件中"modbus"参数为"/dev/ttyUSB0"。USB-RS485转换器在Ubuntu上一般显示为/dev/ttyUSB* or /dev/ttyACM* modbus: "None" or "/dev/ttyUSB0" 注:modbus的参数为string类型,当modbus参数不为"None"时,参数can失效
# 确保requirements.txt安装依赖
# 安装系统级相关驱动
$ pip install minimalmodbus
$ pip install pyserial
$ pip install pymodbus==3.5.1
# 查看USB-RS485端口号
$ ls /dev
# 可以看到类似ttyUSB0端口后给端口执行权限
$ sudo chmod 777 /dev/ttyUSB0
position与手指关节对照表
$ rostopic echo /cb_left_hand_control_cmd
header:
seq: 256
stamp:
secs: 1744343699
nsecs: 232647418
frame_id: ''
name: []
position: [155.0, 162.0, 176.0, 125.0, 255.0, 255.0, 180.0, 179.0, 181.0, 68.0]
velocity: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
L6/O6: ["大拇指弯曲", "大拇指横摆", "食指弯曲", "中指弯曲", "无名指弯曲", "小拇指弯曲"]
L7: ["大拇指弯曲", "大拇指横摆","食指弯曲", "中指弯曲", "无名指弯曲","小拇指弯曲","拇指旋转"]
L10: ["拇指根部", "拇指侧摆","食指根部", "中指根部", "无名指根部","小指根部","食指侧摆","无名指侧摆","小指侧摆","拇指旋转"]
L20: ["拇指根部", "食指根部", "中指根部", "无名指根部","小指根部","拇指侧摆","食指侧摆","中指侧摆","无名指侧摆","小指侧摆","拇指横摆","预留","预留","预留","预留","拇指尖部","食指末端","中指末端","无名指末端","小指末端"]
G20(工业版): ["拇指根部", "食指根部", "中指根部", "无名指根部","小指根部","拇指侧摆","食指侧摆","中指侧摆","无名指侧摆","小指侧摆","拇指横摆","预留","预留","预留","预留","拇指尖部","食指末端","中指末端","无名指末端","小指末端"]
L21: ["大拇指根部", "食指根部", "中指根部","无名指根部","小拇指根部","大拇指侧摆","食指侧摆","中指侧摆","无名指侧摆","小拇指侧摆","大拇指横滚","预留","预留","预留","预留","大拇指中部","预留","预留","预留","预留","大拇指指尖","食指指尖","中指指尖","无名指指尖","小拇指指尖"]
L25: ["大拇指根部", "食指根部", "中指根部","无名指根部","小拇指根部","大拇指侧摆","食指侧摆","中指侧摆","无名指侧摆","小拇指侧摆","大拇指横滚","预留","预留","预留","预留","大拇指中部","食指中部","中指中部","无名指中部","小拇指中部","大拇指指尖","食指指尖","中指指尖","无名指指尖","小拇指指尖"]
控制灵巧手关节角度、获取灵巧手的各种状态信息。
包含了各个产品的使用案例
文档附件目录
已支持的LinkerHand灵巧手产品:L10、L20、L25
$ roscore
$ cd Linker_Hand_SDK_ROS
$ source ./devel/setup.bash
$ rosrun linker_hand_pybullet linker_hand_pybullet.py _hand_type:=L20
参数说明
"_hand_type"数值,无默认,必须根据产品型号选择,例如:_hand_type:=L20
输出结果示例
无
已支持的LinkerHand灵巧手产品:O6/L6/L7/L10/O10/L20/O20/L25 图形界面可控制Mujoco仿真和PyBullet仿真内的灵巧手
图形界面控制可以通过滑动块控制LinkerHand灵巧手O6/L6/L7/L10/O10/L20/O20/L25各个关节独立运动。也可以通过添加按钮记录当前所有滑动块的数值,保存LinkerHand灵巧手当前各个关节运动状态。通过功能性按钮进行动作复现。
使用gui_control控制LinkerHand灵巧手: gui_control界面控制灵巧手需要启动linker_hand_sdk_ros,以topic的形式对LinkerHand灵巧手进行操作。
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手 SDK
$ cd Linker_Hand_SDK_ROS
$ source ./devel/setup.bash
$ roslaunch gui_control gui_control.launch # 控制左手,需要修改launch文件内的配置参数,按照自身需求即可
开启后会弹出UI界面。通过滑动条可控制相应LinkerHand灵巧手关节运动。并可通过右侧添加按钮对当前滑动条数据进行保存,以便用于复现使用。
参数说明
无
输出结果示例
无
"L6": HandConfig(
joint_names_en=["thumb_cmc_pitch", "thumb_cmc_yaw", "index_mcp_pitch", "middle_mcp_pitch", "pinky_mcp_pitch", "ring_mcp_pitch"],
joint_names=["大拇指弯曲", "大拇指横摆", "食指弯曲", "中指弯曲", "无名指弯曲", "小拇指弯曲"],
init_pos=[250] * 6,
preset_actions={
"张开": [250, 250, 250, 250, 250, 250],
"壹": [125, 18, 255, 0, 0, 0],
"贰": [92, 87, 255, 255, 0, 0],
"叁": [92, 87, 255, 255, 255, 0],
"肆": [92, 87, 255, 255, 255, 255],
"伍": [255, 255, 255, 255, 255, 255],
"OK": [96, 100, 118, 250, 250, 250],
"点赞": [250, 79, 0, 0, 0, 0],
"握拳": [102, 18, 0, 0, 0, 0],
# 这里增加动作序列.....
}
),
# 启动SDK后
$ rostopic echo /cb_left_hand_info
data: "{\"version\": [10, 6, 67, 76, 35, 18, 0], \"hand_joint\": \"L10\", \"speed\": [119,\
\ 178, 178, 178, 178, -1, -1, -1, -1, -1], \"current\": [null, null, null, null,\
\ null, null, null, null, null, null], \"fault\": [0, 0, 0, 0, 0, 0, 0, 0, 0, 0],\
\ \"motor_temperature\": [32, 35, 34, 31, 34, 33, 34, 36, 33, 38], \"is_touch\"\
: true, \"touch_type\": 2, \"finger_order\": []}"
参数说明 version: 版本编号 hand_joit: 灵巧手型号 speed: 当前速度阈值 current: 当前电流 null为暂不支持 fault: 对应电机错误码 0为正常 motor_temperature: 对应电机温度 is_touch: 是否支持压力传感器 touch_type: 压感模式,1、法向压力传感器。 2、矩阵压力传感器
已支持的LinkerHand灵巧手产品:L10、L20
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
$ cd Linker_Hand_SDK_ROS
$ source ./devel/setup.bash
$ rosrun set_linker_hand_speed set_linker_hand_speed.py _hand_type:=left _speed:=[180,250,250,250,250] # L7为7个值,其他为5个值
参数说明
L10、L20:5个手指统一的速度
speed:=[180,250,250,250,250]
L7:7个电机速度
speed:=[180,250,250,250,250,250,250]
输出结果示例
speed:[180,250,250,250,250]
已支持的LinkerHand灵巧手产品:L10、L20
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
$ cd Linker_Hand_SDK_ROS
$ source ./devel/setup.bash
$ rosrun set_linker_hand_current set_linker_hand_current.py _hand_type:=left _current:=42 #暂不支持L7
参数说明
参数:hand_type: left | right 左手还是右手 current:0~255 设置最大电流值
输出结果示例
current:[180,250,250,250,250]
已支持的LinkerHand灵巧手产品:L10、L20
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
$ cd Linker_Hand_SDK_ROS
$ source ./devel/setup.bash
$ rosrun set_linker_hand_torque set_linker_hand_torque.py _hand_type:=left _torque:=[180,250,250,250,250] # L7为7个值,其他为5个值
参数说明
参数:hand_type: left | right 左手还是右手 torque:=[180,250,250,250,250] 0~255 L7为7个电机最大值,其他为5个手指最大值
输出结果示例
torque:[180,250,250,250,250]
已支持的LinkerHand灵巧手产品:L25
使灵巧手电机失能,可随意拖动各个关节活动
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand_l25.launch # 启动L25
$ Linker_Hand_SDK_ROS/src/linker_hand_sdk/examples/L25
$ python set_disability.py
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L25
使灵巧手电机使能,使能后,可用控制程序控制
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动
$ Linker_Hand_SDK_ROS/src/linker_hand_sdk/examples/L25
$ python set_enable.py
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L25
如果拥有多只相同版本L25灵巧手,可使用本示例完成:一只失能的灵巧手控制另一只使能的灵巧手
首先需要启动LinkerHand SDK ROS 以下为被控制L25灵巧手配置方式,以下以右手为例 首先确保两台Ubuntu在同一网络内,并且配置好主从,两台Ubuntu可同时进行ROS通讯,可参考ROS官方文档
控制方-A灵巧手配置
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动
$ Linker_Hand_SDK_ROS/src/linker_hand_sdk/examples/L25
$ python set_remote_control.py
被控制方-B灵巧手配置
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch
此时,手动拖拽A机器的失能L25灵巧手即可控制B机器的使能L25灵巧手。
已支持的LinkerHand灵巧手产品:L10、L20
注:需要有RGB摄像头
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ rosrun finger_guessing finger_guessing.py
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L20
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
python ./<你的文件路径>/lipcontroller.py
如终端打印出“开始演示”即为正常运行,此时手设置如果正确,应开始使用食指和中指进行捏的动作,捏到物品会停止,拿走物品后会继续尝试捏,直到捏到物品或运动到极限。
lipcontroller.py 是基于产品O7的第7版进行开发的演示demo,应用在其他版本的演示时,需要调整拇指和食指的对合姿态,否则无法实现“食指和拇指捏合在一起”的动作。
参数说明
无
输出结果示例
无
使用本例硬件为LinkerRobot人形机器人,也可以使用其他机械臂或机器人进行模仿学习训练,只要修改该相应数据话题即可, 详细使用说明请参考human-dex项目README.md
cd human-dex conda create -n human-dex python=3.8.10 conda activate human-dex pip install torchvision pip install torch pip install -r requirements.txt
mkdir -p your_ws/src
cd your_ws/src
git clone https://github.com/linker-bot/human-dex.git
cd ..
catkin_make
source ./devel/setup.bash
# 数据采集
roslaunch record_hdf5 record_hdf5.launch
# 新开终端发送采集命令
rostopic pub /record_hdf5 std_msgs/String "data: '{\"method\":\"start\",\"type\":\"humanplus\"}'"
cd humanplus/scripts/utils/HIT python3 imitate_episodes_h1_train.py --task_name data_cb_grasp --ckpt_dir cb_grasp/ --policy_class HIT --chunk_size 50 --hidden_dim 512 --batch_size 48 --dim_feedforward 512 --lr 1e-5 --seed 0 --num_steps 100000 --eval_every 1000 --validate_every 1000 --save_every 1000 --no_encoder --backbone resnet18 --same_backbones --use_pos_embd_image 1 --use_pos_embd_action 1 --dec_layers 6 --gpu_id 0 --feature_loss_weight 0.005 --use_mask --data_aug
cd humanplus/scripts
python3 cb.py
参数说明
无
输出结果示例
无
原Unidexgrasp算法采用shadowhand,以下提供在linkerhand上开发Unidexgrasp算法的相关代码。 详细过程参考linker_unidexgrasp项目
抓取姿态生成部分
抓取姿态部分采取映射方案,将模型输出的shadowhand手姿,映射为linkerHand L20手姿态,为后续开发使用。
conda create -n unidexgrasp python=3.8
conda activate unidexgrasp
conda install -y pytorch==1.10.0 torchvision==0.11.0 torchaudio==0.10.0 cudatoolkit=11.3 -c pytorch -c conda-forge
conda install -y https://mirrors.bfsu.edu.cn/anaconda/cloud/pytorch3d/linux-64/pytorch3d-0.6.2-py38_cu113_pyt1100.tar.bz2
pip install -r requirements.txt
cd thirdparty/pytorch_kinematics
pip install -e .
cd ../nflows
pip install -e .
cd ../
git clone https://github.com/wrc042/CSDF.git
cd CSDF
pip install -e .
cd ../../
训练
python ./network/train.py --config-name ipdf_config \ --exp-dir ./ipdf_train
python ./network/train.py --config-name glow_config \ --exp-dir ./glow_train python ./network/train.py --config-name glow_joint_config \ --exp-dir ./glow_train
python ./network/train.py --config-name cm_net_config \ --exp-dir ./cm_net_train
验证
python ./network/eval.py --config-name eval_config \ --exp-dir=./eval
python ./tests/visualize_result_l20_shadow.py --exp_dir 'eval' --num 3
python ./tests/data_for_RL.py
已支持的LinkerHand灵巧手产品:L20
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
python ./<你的文件路径>/gesture-Show-OK.py
开始后终端会打印测试中,此时手会开始做OK手势,并弯曲中指无名指小指和伸直动作。
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L20
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
python ./<你的文件路径>/gesture-Show-Surround-Index-Finger.py
开始后终端会打印测试中,此时手会开始握拳并伸出食指,食指会不断重复旋转。
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L20
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
python ./<你的文件路径>/gesture-Show-Wave.p
开始后终端会打印测试中,此时手拇指向外舒展不动,其余四指开始做波浪运动。
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L20
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动灵巧手
python ./<你的文件路径>/gesture-Show-Ye.py
开始后终端会打印测试中,此时手会开始做一套复杂动作来展示手的灵活性。
本例是基于产品O7的第7版进行开发的演示demo,应用在其他版本的演示时,需要调整拇指和食指的对合姿态,否则无法实现“食指和拇指捏合或对合在一起”的动作。
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L20
$ roscore
$ cd Linker_Hand_SDK_ROS/
$ source ./devel/setup.bash
$ roslaunch linker_hand_sdk_ros linker_hand.launch # 启动 L10 or L20 灵巧手
$ cd Linker_Hand_SDK_ROS/src/linker_hand_sdk/examples/gesture-show
$ python gesture-Loop.py
参数说明
无
输出结果示例
无
已支持的LinkerHand灵巧手产品:L25
参数说明
无
输出结果示例
无
Human-Dex:https://github.com/linkerbotai/human-dex
Linker_UniDexGrasp:https://github.com/linkerbotai/linker_unidexgrasp
LinkerHand-Python-SDK:https://github.com/linkerbotai/linker_hand_python_sdk
linker_serl:https://github.com/linkerbotai/linker_serl
pip install python-can
方法一
$ sudo visudo
#添加以下内容
你的用户名 ALL=(ALL) NOPASSWD: /sbin/ip
你的用户名 ALL=(ALL) NOPASSWD: /usr/sbin/ip link set can0 up type $ $ can bitrate 1000000
# 保存退出
方法二
修改setting.yaml配置文件的密码,默认PASSWORD:"12345678"