ArUco码驱动合作目标灵巧操控

Gazebo仿真环境搭建

1、SolidWorks export as urdf插件(只有装配体才适用)
2、单零件装配体尽量使用多个link,而非单个base_link
3、base_link相当于虚拟的存在,改变mass无影响,关键在于chaid_link的属性,mass和interia要大,相当于压住整个物体的意思。
4、加入材料/颜色属性

  <gazebo reference="base_link">
     <material>Gazebo/Orange</material>
     <turnGravityOff>false</turnGravityOff>
  </gazebo>

5、零件图和装配体坐标系一定要处理好,现在处理不好会留下后患,基本思路为装配体中心放在坐标系中心上,配合好后通过移动零部件实现,坐标系位置可以用点和坐标系重合配合实现。
6、调整好坐标系关系后,urdf导出尽量使用默认配置,防止出现问题。

ArUco码位姿信息监听

buffer = tf2_ros.Buffer()	#初始化缓冲区
listener = tf2_ros.TransformListener(buffer)	#初始化监听对象

trans = buffer.lookup_transform("world","camera_marker",rospy.Time(0),rospy.Duration(5.0))

回传的trans数据类型为“TransformStamped”

[geometry_msgs/TransformStamped]:
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
string child_frame_id
geometry_msgs/Transform transform
  geometry_msgs/Vector3 translation
    float64 x
    float64 y
    float64 z
  geometry_msgs/Quaternion rotation
    float64 x
    float64 y
    float64 z
    float64 w

赋值要注意数据类型

当前位姿信息回传及单步驱动

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import rospy, sys
import _thread, copy
import moveit_commander
from moveit_commander import RobotCommander, MoveGroupCommander, PlanningSceneInterface
from geometry_msgs.msg import PoseStamped, Pose
from moveit_msgs.msg import CollisionObject, AttachedCollisionObject, PlanningScene
from math import radians
from copy import deepcopy
import tf2_ros
from tf_trans import tf_listener


# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)

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

# 初始化场景对象,用来监听外部环境的变化
scene = PlanningSceneInterface()
# rospy.sleep(1)
        
# 初始化需要使用move group控制的机械臂中的arm group
ur = moveit_commander.MoveGroupCommander('manipulator')
gripper = moveit_commander.MoveGroupCommander('gripper') 

end_effector_link = 'yixiuge_ee_link'

# 设置目标位置所使用的参考坐标系
reference_frame = 'world'
gripper.set_pose_reference_frame(reference_frame)
        
# 当运动规划失败后,允许重新规划
gripper.allow_replanning(True)


# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
gripper.set_goal_position_tolerance(0.05)
gripper.set_goal_orientation_tolerance(0.05)

# 设置允许的最大速度和加速度
ur.set_max_acceleration_scaling_factor(0.5)
ur.set_max_velocity_scaling_factor(0.5)
ur.set_max_acceleration_scaling_factor(0.5)
ur.set_max_velocity_scaling_factor(0.5)


# 控制机械臂先回到初始化位置
ur.set_named_target('yixiuge_home')
ur.go()

buffer = tf2_ros.Buffer()	#初始化缓冲区
listener = tf2_ros.TransformListener(buffer)	#初始化监听对象

trans = buffer.lookup_transform("world","camera_marker",rospy.Time(0),rospy.Duration(5.0))

#tfl = tf.TransformListener()
#(trans,rot) = tfl.lookupTransform('world', 'camera_marker', rospy.Time(0))

print(trans)
# 设置机械臂工作空间中的目标位姿,位置使用x、y、z坐标描述,
# 姿态使用四元数描述,基于base_link坐标系
target_pose1 = PoseStamped()


#参考坐标系,前面设置了
target_pose1.header.frame_id = reference_frame
target_pose1.header.stamp = rospy.Time.now() #时间戳?

#末端位置2,右手预备位置1   
target_pose1.pose.position.x = trans.transform.translation.x
target_pose1.pose.position.y = trans.transform.translation.y - 0.1
target_pose1.pose.position.z = trans.transform.translation.z + 0.6
#末端姿态,四元数
target_pose1.pose.orientation.x = 0
target_pose1.pose.orientation.y = 0
target_pose1.pose.orientation.z = 0
target_pose1.pose.orientation.w = 1

# 设置机器臂当前的状态作为运动初始状态

ur.set_start_state_to_current_state()

# 设置机械臂终端运动的目标位姿

ur.set_pose_target(target_pose1, end_effector_link)
ur.go()

rospy.sleep(1)

gripper.set_named_target("close")
gripper.go()

rospy.sleep(1)

gripper.set_named_target("open")
gripper.go()

rospy.sleep(1)

# 控制机械臂先回到初始化位置
ur.set_named_target('yixiuge_home')
ur.go()	


# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)


  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值