kinova-jaco2使用Moveit!控制真实机械臂抓取固定点物体

一、机械臂坐标系

1、坐标系方向

遵循右手法则:右手手背正对机械臂数据接口槽,四指方向为x,拇指方向为z,垂直手心方向为y
在这里插入图片描述

2、位姿方向

逆时针为正
在这里插入图片描述

3、z轴的起始点

如下图所示,origin所在平面z值为0,机械臂最底下的关节平面为origin。j2n6s300_end_effector的位置为第六个关节向下160mm处,实物上即最后一节手指关节上螺丝的上端。
在这里插入图片描述

二、启动机械臂和Moveit!

   sudo cp ~/jaco2_ws/src/kinova-ros-master/kinova_driver/udev/10-kinova-arm.rules /etc/udev/rules.d/
   roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300
   roslaunch j2n6s300_moveit_config j2n6s300_demo.launch 

三、实现抓取

1、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

class MoveItIkDemo:
    def __init__(self):
        # 初始化move_group的API
        moveit_commander.roscpp_initialize(sys.argv)

        # 初始化ROS节点
        rospy.init_node('real_jaco_moveit_fixed_grasp')

        # 初始化需要使用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.32
        target_pose.pose.position.y = 0.2
        target_pose.pose.position.z = 0
        target_pose.pose.orientation.x = 0.14578
        target_pose.pose.orientation.y = 0.98924
        target_pose.pose.orientation.z = -0.0085346
        target_pose.pose.orientation.w = 0.0084136
        # 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()


2、python文件建议直接用python启动

python2 real_jaco_moveit_fixed_grasp.py 

手臂以竖直的姿态抓取物体。

如果启动不了,在目录下给一下权限

chmod +x real_jaco_moveit_fixed_grasp.py

四、遇到的问题

1、逆运动学无解的问题

2020-5-26更新,想得到桌子上的一些点,所以重新运行了一下,但是一直报这两个错误
错误:
(1)[ERROR] [1590499013.878968250]: RRTConnect: Unable to sample any valid states for goal tree
在这里插入图片描述
(2)[ WARN] [1590499013.886385474]: Fail: ABORTED: No motion plan found. No execution attempted.
在这里插入图片描述

解决:
其实就是逆运动学求解没有求到。将四元素改到两位小数精度也没有用,最后改成了[0,1,0,1]就可以了。

  • 7
    点赞
  • 101
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 4
    评论
评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

这是一个图像

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值