Moblie-Aloha家务机器人-8.Aloha手臂主从控制(ROS1)

运行以下指令:

roslaunch interbotix_xsarm_puppet xsarm_puppet.launch robot_model_master:=wx250s robot_model_puppet:=vx300s use_sim:=true

一主一从ROS1.png

cd ~/interbotix_ws/src/interbotix_ros_manipulators/interbotix_ros_xsarms/examples/python_demos

添加并修改bartender_master.py

bot = InterbotixManipulatorXS(
        robot_model='wx250s',
        robot_name = 'master',
        group_name='arm',
        gripper_name='gripper'
    )

具体代码如下,此处屏蔽了夹手动作:

from interbotix_xs_modules.arm import InterbotixManipulatorXS
import numpy as np
import sys

# This script makes the end-effector perform pick, pour, and place tasks
# Note that this script may not work for every arm as it was designed for the wx250
# Make sure to adjust commanded joint positions and poses as necessary
#
# To get started, open a terminal and type 'roslaunch interbotix_xsarm_control xsarm_control.launch robot_model:=wx250'
# Then change to this directory and type 'python bartender.py  # python3 bartender.py if using ROS Noetic'

def main():
    #bot = InterbotixManipulatorXS("wx250s", "arm", "gripper")
    bot = InterbotixManipulatorXS(
    robot_model='wx250s',
    robot_name = 'master',
    group_name='arm',
    gripper_name='gripper'
    )
   

    if (bot.arm.group_info.num_joints < 5):
        print('This demo requires the robot to have at least 5 joints!')
        sys.exit()

    bot.arm.set_ee_pose_components(x=0.3, z=0.2)
    bot.arm.set_single_joint_position("waist", np.pi/2.0)
    #bot.gripper.open()
    bot.arm.set_ee_cartesian_trajectory(x=0.1, z=-0.16)
    #bot.gripper.close()
    bot.arm.set_ee_cartesian_trajectory(x=-0.1, z=0.16)
    bot.arm.set_single_joint_position("waist", -np.pi/2.0)
    bot.arm.set_ee_cartesian_trajectory(pitch=1.5)
    bot.arm.set_ee_cartesian_trajectory(pitch=-1.5)
    bot.arm.set_single_joint_position("waist", np.pi/2.0)
    bot.arm.set_ee_cartesian_trajectory(x=0.1, z=-0.16)
    #bot.gripper.open()
    bot.arm.set_ee_cartesian_trajectory(x=-0.1, z=0.16)
    bot.arm.go_to_home_pose()
    bot.arm.go_to_sleep_pose()

if __name__=='__main__':
    main()



修改master_modes.yaml

port: /dev/ttyUSB0
 
groups:
  arm:
    operating_mode: position
    profile_type: time
    profile_velocity: 0
    profile_acceleration: 0
    torque_enable: true
 
singles:
  gripper:
    operating_mode: pwm
torque_enable: true

修改puppet_modes.yaml

port: /dev/ttyUSB1
 
groups:
  arm:
    operating_mode: position
    profile_type: time
    profile_velocity: 0
    profile_acceleration: 0
    torque_enable: true
 
singles:
  gripper:
    operating_mode: pwm
    profile_type: time
    profile_velocity: 0
    profile_acceleration: 0
    torque_enable: true


python3 bartender_master.py

一主一从ROS1 2.png

一主一从ROS1控制仿真.jpg

以上操作均为仿真操作

实际测试:

警告:此操作的前提是机械臂运动空间没有限制,可以自由运动,安装在静态ALOHA2的机械臂,由于外框限制以及手臂限制,操作可能会引发干涉,谨慎使用!
新建aloha_master_puppet_test.py

from interbotix_xs_modules.arm import InterbotixManipulatorXS
import numpy as np
import sys

# This script makes the end-effector perform pick, pour, and place tasks
# Note that this script may not work for every arm as it was designed for the wx250
# Make sure to adjust commanded joint positions and poses as necessary
#
# To get started, open a terminal and type 'roslaunch interbotix_xsarm_control xsarm_control.launch robot_model:=wx250'
# Then change to this directory and type 'python bartender.py  # python3 bartender.py if using ROS Noetic'

def main():
    #bot = InterbotixManipulatorXS("wx250s", "arm", "gripper")
    bot = InterbotixManipulatorXS(
    robot_model='wx250s',
    robot_name = 'master',
    group_name='arm',
    gripper_name='gripper'
    )
   

    if (bot.arm.group_info.num_joints < 5):
        print('This demo requires the robot to have at least 5 joints!')
        sys.exit()

    bot.arm.set_ee_pose_components(x=0.3, z=0.2)
    #bot.arm.set_single_joint_position("waist", np.pi/2.0)
    #bot.gripper.open()
    #bot.arm.set_ee_cartesian_trajectory(x=0.1, z=-0.16)
    #bot.gripper.close()
    #bot.arm.set_ee_cartesian_trajectory(x=-0.1, z=0.16)
    #bot.arm.set_single_joint_position("waist", -np.pi/2.0)
    #bot.arm.set_ee_cartesian_trajectory(pitch=1.5)
    #bot.arm.set_ee_cartesian_trajectory(pitch=-1.5)
    #bot.arm.set_single_joint_position("waist", np.pi/2.0)
    #bot.arm.set_ee_cartesian_trajectory(x=0.1, z=-0.16)
    #bot.gripper.open()
    bot.arm.set_ee_cartesian_trajectory(x=-0.1, z=0.16)
    bot.arm.go_to_home_pose()
    #bot.arm.go_to_sleep_pose()

if __name__=='__main__':
    main()

测试

roslaunch interbotix_xsarm_puppet xsarm_puppet.launch robot_model_master:=wx250s robot_model_puppet:=vx300s 


cd ~/interbotix_ws/src/interbotix_ros_manipulators/interbotix_ros_xsarms/examples/python_demos


python3 aloha_master_puppet_test.py