• Ubuntu18.04系统下通过moveit控制kinova真实机械臂,并用python脚本到达固定点


    测试工作空间:test_ws
    Kinova机械臂型号:m1n6s300
    双臂模型中的左臂
    测试功能包为kinova-ros官方包

    一、读取kinova机械臂末端执行器位姿及tf小知识

    1. tf小知识之获取两个连杆坐标系的位姿关系,非常有用,非常有用,非常有用!!!

    我们一般通过以下命令获取机械臂末端相对基座的位姿,注意这里基坐标在前,末端执行器在后。也就是我们希望获得m1n6s300_end_effector坐标系相对于root坐标系的关系。

    重要,重要,重要

    rosrun tf tf_echo root m1n6s300_end_effector
    
    • 1

    这里的姿态有四元素以及RPY的弧度制和角度制三种表示,非常方便,他的发布是实时的。

    这里四元数Quaternion的顺序是(x y z w),虚部w在后

    在这里插入图片描述

    2. 查看机械臂末端执行器位姿方法二,通过moveit

    启动机械臂moveit(后面会讲到),在Rviz中查看末端执行器的位置姿态。Displays -> MotionPlanning -> Scene Robot -> Links,可以查看每个连杆的位置姿态。如m1n6s300_end_effector相对于root的位姿,这里看到的与前面通过tf tf_echo命令得到的是一致的

    在这里插入图片描述

    二、通过moveit!的小球控制真实机械臂运动

    1.启动机械臂驱动

    roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=m1n6s300 kinova_robotSerial:=PJ00650019162710001
    
    • 1

    2.启动moveit

    roslaunch m1n6s300_moveit_config m1n6s300_demo.launch 
    
    • 1

    此时可以拖动小球,进行机械臂的运动控制,点击Plan和Excute后,RViz中的机械臂和真实机械臂均会运动。

    在这里插入图片描述
    3.通过python脚本控制机械臂运动,这里会用到moveit的规划函数。因此先运行1和2的命令,即启动机械臂驱动和moveit

    test_ws/src/kinova-ros/kinova_demo/nodes/kinova_demo路径下创建名为real_left_arm_demo.py的python脚本
    内容如下:

    #!/usr/bin/env python
    # -*- coding: utf-8 -*-
    
    import rospy, sys
    import moveit_commander
    from moveit_commander import PlanningSceneInterface
    from geometry_msgs.msg import PoseStamped
    # PoseStamped:A Pose with reference coordinate frame and timestamp,具有参考坐标系和时间戳的位姿
    
    
    class MoveItIkDemo:
        def __init__(self):
            # 初始化move_group的API
            moveit_commander.roscpp_initialize(sys.argv)
    
            # 初始化ROS节点
            rospy.init_node('real_left_arm_demo')
    
            # 初始化需要使用move group控制的机械臂中的arm group
            arm = moveit_commander.MoveGroupCommander('arm')
    
            # 初始化需要使用move group控制的机械臂中的gripper group
            gripper = moveit_commander.MoveGroupCommander('gripper')
    
            # 获取终端link的名称
            end_effector_link = arm.get_end_effector_link()
    
            # 设置目标位置所使用的参考坐标系
            reference_frame = 'world'
            arm.set_pose_reference_frame(reference_frame)
    
            # 当运动规划失败后,允许重新规划
            arm.allow_replanning(True)
    
            # 设置位置(单位:米)和姿态(单位:弧度)的允许误差
            arm.set_goal_position_tolerance(0.001)
            arm.set_goal_orientation_tolerance(0.001)
            gripper.set_goal_joint_tolerance(0.001)
    
            # 设置允许的最大速度和加速度
            arm.set_max_acceleration_scaling_factor(0.5)
            arm.set_max_velocity_scaling_factor(0.5)
    
            # 初始化场景对象
            scene = PlanningSceneInterface()
            rospy.sleep(1)
    
            # 控制机械臂先回到初始化位置,手爪打开
            arm.set_named_target('Home')
            arm.go()
            gripper.set_named_target('Open')
            gripper.go()
            rospy.sleep(1)
    
            # 设置机械臂工作空间中的目标位姿,位置使用x、y、z坐标描述,
            # 姿态使用四元数描述,基于base_link坐标系
            target_pose = PoseStamped()
            target_pose.header.frame_id = reference_frame
            target_pose.header.stamp = rospy.Time.now()
            target_pose.pose.position.x = 0.211
            target_pose.pose.position.y = -0.3
            target_pose.pose.position.z = 0.40
            target_pose.pose.orientation.x = 0.5
            target_pose.pose.orientation.y = 0.5
            target_pose.pose.orientation.z = 0.5
            target_pose.pose.orientation.w = 0.5
            # thing_pose.pose.orientation.x =  -0.59375
            # thing_pose.pose.orientation.y = -0.60903
            # thing_pose.pose.orientation.z = -0.13927
            # thing_pose.pose.orientation.w = 0.5071
            # 设置机器臂当前的状态作为运动初始状态
            arm.set_start_state_to_current_state()
            # 设置机械臂终端运动的目标位姿
            arm.set_pose_target(target_pose, end_effector_link)
            # 规划运动路径
            traj = arm.plan()
            # 按照规划的运动路径控制机械臂运动
            arm.execute(traj)
            rospy.sleep(1)
            # 设置夹爪的目标位置,并控制夹爪运动
            gripper.set_named_target('Close')
            gripper.go()
            rospy.sleep(1)
    
    
    
            # # 控制机械臂先回到初始化位置,手爪闭合
            # arm.set_named_target('Home')
            # arm.go()
            # gripper.set_named_target('Close')
            # gripper.go()
    
            # 关闭并退出moveit
            moveit_commander.roscpp_shutdown()
            moveit_commander.os._exit(0)
    
    
    if __name__ == "__main__":
        MoveItIkDemo()
    
    
    
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16
    • 17
    • 18
    • 19
    • 20
    • 21
    • 22
    • 23
    • 24
    • 25
    • 26
    • 27
    • 28
    • 29
    • 30
    • 31
    • 32
    • 33
    • 34
    • 35
    • 36
    • 37
    • 38
    • 39
    • 40
    • 41
    • 42
    • 43
    • 44
    • 45
    • 46
    • 47
    • 48
    • 49
    • 50
    • 51
    • 52
    • 53
    • 54
    • 55
    • 56
    • 57
    • 58
    • 59
    • 60
    • 61
    • 62
    • 63
    • 64
    • 65
    • 66
    • 67
    • 68
    • 69
    • 70
    • 71
    • 72
    • 73
    • 74
    • 75
    • 76
    • 77
    • 78
    • 79
    • 80
    • 81
    • 82
    • 83
    • 84
    • 85
    • 86
    • 87
    • 88
    • 89
    • 90
    • 91
    • 92
    • 93
    • 94
    • 95
    • 96
    • 97
    • 98
    • 99
    • 100
    • 101
    • 102

    注意,左臂末端朝下抓取的四元素是0.5 0.5 0.5 0.5

    进入该脚本文件夹,执行以下命令即可

    python2 real_left_arm_demo.py
    
    • 1

    这里如果启动不了,在目录下给一下权限即可:

    chmod +x real_left_arm_demo.py
    
    • 1

    该代码来自:https://blog.csdn.net/puqian13/article/details/100901291

    感谢大佬分享。

    在这里插入图片描述

  • 相关阅读:
    SSH在线考试系统
    DAY29:Vulnhub--靶机实战
    MySQL如何进行增量备份与恢复?
    2010年408计网
    【愚公系列】2022年08月 Go教学课程 040-字符串处理
    人工智能基础_机器学习026_L1正则化_套索回归权重衰减梯度下降公式_原理解读---人工智能工作笔记0066
    洛谷P4213 杜教筛模板
    花费半年整理拼多多、饿了么、蚂蚁金服等大厂Java面试题大集合
    MATLAB-图像加密
    数据结构与算法编程题8
  • 原文地址:https://blog.csdn.net/Time_Memory_cici/article/details/132701246