官网教程:Python Demos — Interbotix X-Series Arms Documentation
系统:Ubuntu20.04,ROS1
硬件:2台WidowX-250s机械臂、1台笔记本电脑、1个相机(后续的模仿学习中会用到)
相关的机械臂硬件连接跳过 ~~~
1.硬件与软件配置
首先是主从机械臂的定义:
因为原先完成了aloha相关项目的配置,所以对于这次的2个WidowX-250s机械臂的序列号配置,依然保留原先的命名风格。
主动端的机械臂序列号名称定义为:/dev/ttyDXL_master_left
从动端的机械臂序列号名称定义为:/dev/ttyDXL_master_right
从动端的机械臂末端处的相机序列号名称定义为:/dev/CAM_ARM_WRIST
可以理解为left为主,right为从,即:master_side对应的config文件为master_modes_left.yaml;salve_side对应的config文件为puppet_modes_left.yaml,命名后缀统一为left。
yaml文件内容具体如下:
master_modes_left.yaml:
puppet_modes_left.yaml:
接下来给出主动端与从动端的launch文件:
主动端 master.launch:
<launch><arg name="robot_model_master" default="wx250s"/><arg name="base_link_master" default="base_link"/><arg name="master_node" default="$(find aloha)/config_single/master_modes_left.yaml"/><arg name="launch_driver" default="true"/><arg name="use_sim" default="false"/><arg name="robot" value="master_left"/><include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch"><arg name="robot_model" value="$(arg robot_model_master)"/><arg name="robot_name" value="$(arg robot)"/><arg name="base_link_frame" value="$(arg base_link_master)"/><arg name="use_world_frame" value="false"/><arg name="use_rviz" value="false"/><arg name="mode_configs" value="$(arg master_node)"/><arg name="use_sim" value="$(arg use_sim)"/></include><nodename="master_left_transform_broadcaster"pkg="tf2_ros"type="static_transform_publisher"args="0 -0.25 0 0 0 0 /world /$(arg robot)/base_link"/></launch>
从动端 robot.launch:
<launch><arg name="robot_model_puppet" default="wx250s"/><arg name="base_link_puppet" default="base_link"/><arg name="puppet_modes_left" default="$(find aloha)/config_single/puppet_modes_left.yaml"/><arg name="launch_driver" default="true"/><arg name="use_sim" default="false"/><arg name="robot" value="puppet_left"/><include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch"><arg name="robot_model" value="$(arg robot_model_puppet)"/><arg name="robot_name" value="$(arg robot)"/><arg name="base_link_frame" value="$(arg base_link_puppet)"/><arg name="use_world_frame" value="false"/><arg name="use_rviz" value="false"/><arg name="mode_configs" value="$(arg puppet_modes_left)"/><arg name="use_sim" value="$(arg use_sim)"/></include><node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" ><param name="video_device" value="/dev/CAM_ARM_WRIST" /><param name="framerate" value="60" /><param name="image_width" value="640" /><param name="image_height" value="480" /><param name="pixel_format" value="yuyv" /><param name="camera_frame_id" value="usb_cam" /><param name="io_method" value="mmap"/><param name="autofocus" value="false"/><param name="focus" value="40"/><param name="autoexposure" value="true"/></node></launch>
对应的constants.py文件中的夹爪启动控制数值,要注意:
# Left finger position limits (qpos[7]), right_finger = -1 * left_finger
MASTER_GRIPPER_POSITION_OPEN = 0.02417
MASTER_GRIPPER_POSITION_CLOSE = 0.01244
PUPPET_GRIPPER_POSITION_OPEN = 0.05800
PUPPET_GRIPPER_POSITION_CLOSE = 0.01844# Gripper joint limits (qpos[6])
MASTER_GRIPPER_JOINT_OPEN = 0.3083 # noetic
MASTER_GRIPPER_JOINT_CLOSE = -0.6842 # noetic
PUPPET_GRIPPER_JOINT_OPEN = 1.4910
PUPPET_GRIPPER_JOINT_CLOSE = -0.6213
对应的one_side_teleop_single_arm.py文件中的代码为:
import time
import sys
import IPython
e = IPython.embedfrom interbotix_xs_modules.arm import InterbotixManipulatorXS
from interbotix_xs_msgs.msg import JointSingleCommand
from constants import MASTER2PUPPET_JOINT_FN, DT, START_ARM_POSE, MASTER_GRIPPER_JOINT_MID, PUPPET_GRIPPER_JOINT_CLOSE, MASTER_GRIPPER_JOINT_CLOSE, MASTER_GRIPPER_JOINT_OPEN
from robot_utils import torque_on, torque_off, move_arms, move_grippers, get_arm_gripper_positionsdef prep_robots(master_bot, puppet_bot):# reboot gripper motors, and set operating modes for all motorspuppet_bot.dxl.robot_reboot_motors("single", "gripper", True)puppet_bot.dxl.robot_set_operating_modes("group", "arm", "position")puppet_bot.dxl.robot_set_operating_modes("single", "gripper", "current_based_position")master_bot.dxl.robot_set_operating_modes("group", "arm", "position")master_bot.dxl.robot_set_operating_modes("single", "gripper", "position")# puppet_bot.dxl.robot_set_motor_registers("single", "gripper", 'current_limit', 1000) # TODO(tonyzhaozh) figure out how to set this limittorque_on(puppet_bot)torque_on(master_bot)# move arms to starting positionstart_arm_qpos = START_ARM_POSE[:6]move_arms([master_bot, puppet_bot], [start_arm_qpos] * 2, move_time=1)# move grippers to starting positionmove_grippers([master_bot, puppet_bot], [MASTER_GRIPPER_JOINT_MID, MASTER_GRIPPER_JOINT_OPEN], move_time=0.5)def press_to_start(master_bot):# press gripper to start data collection# disable torque for only gripper joint of master robot to allow user movementmaster_bot.dxl.robot_torque_enable("single", "gripper", False)print(f'Close the gripper to start')close_thresh = -0.3pressed = Falsewhile not pressed:gripper_pos = get_arm_gripper_positions(master_bot)print(gripper_pos)if gripper_pos < close_thresh:pressed = Truetime.sleep(DT/10)torque_off(master_bot)print(f'Started!')def teleop():""" A standalone function for experimenting with teleoperation. No data recording. """puppet_bot_left = InterbotixManipulatorXS(robot_model="wx250s", group_name="arm", gripper_name="gripper", robot_name=f'puppet_left', init_node=True)master_bot_left = InterbotixManipulatorXS(robot_model="wx250s", group_name="arm", gripper_name="gripper", robot_name=f'master_left', init_node=False)prep_robots(master_bot_left, puppet_bot_left)press_to_start(master_bot_left)### Teleoperation loopgripper_command = JointSingleCommand(name="gripper")while True:# sync joint positionsmaster_state_joints = master_bot_left.dxl.joint_states.position[:6]puppet_bot_left.arm.set_joint_positions(master_state_joints, blocking=False)# sync gripper positionsmaster_gripper_joint = master_bot_left.dxl.joint_states.position[6]# puppet_gripper_joint_target = MASTER2PUPPET_JOINT_FN(master_gripper_joint)puppet_gripper_joint_target = master_gripper_jointgripper_command.cmd = puppet_gripper_joint_targetpuppet_bot_left.gripper.core.pub_single.publish(gripper_command)# sleep DTtime.sleep(DT)if __name__=='__main__':teleop()
最后注意:
go to
~/interbotix_ws/src/interbotix_ros_toolboxes/interbotix_xs_toolbox/interbotix_xs_modules/src/interbotix_xs_modules/arm.py
,find function
publish_positions
.Change
self.T_sb = mr.FKinSpace(self.robot_des.M, self.robot_des.Slist, self.joint_commands)
toself.T_sb = None
.This prevents the code from calculating FK at every step which delays teleoperation.
2.遥操作启动指令
对应的遥操作launch启动指令为:
roslaunch master.launch
roslaunch robot.launch
对应的遥操作python启动指令为:
cd /single-aloha/aloha_scripts
conda activate aloha
python one_side_teleop_single_arm.py
即可启动机械臂,进行遥操作!
参考:
https://github.com/tonyzhaozh/aloha
https://github.com/MarkFzp/mobile-aloha