【机械臂】【基本驱动】三、对于夹取物体bug的最新解决

系列概述

临近本科毕业,考虑到未来读研的方向以及自己的兴趣方向,我选择的课题大致为"基于VLA结构的指令驱动式机械臂仿真系统的实现"。

为什么说是VLA(Vision-Language-Action)"结构",因为就目前而言,我认为在目前剩下的几个月时间内从0实现一个正儿八经的VLA模型,所需要的时间、资金、模型资源的获取都是比较麻烦的。因此,我选择使用ROS1+LLM+视觉算法来实现一个"伪VLA"结构,就目前阶段(开题一个月)而言,我能给出的场景示意如下:

场景:指令输入"机械臂将蓝色方块夹起放到红色圆柱体上面",系统接收指令后,先通过视觉模块确定当前系统中各个物体的坐标,再通过开源大模型,结合已知坐标信息,通过预设的prompt生成动作序列,作为参数送入ROS1架构下的启动文件中,实现动作行为在gazebo下的仿真。

当前阶段我能给出粗糙的逻辑示意图如下:

接下来,我将给出目前阶段我所计划的步骤实现,之后该系列的博客都会依照下面的框架进行更新。由于我也是初次入门ROS以及深度学习相关的内容,所以本系列博客更多的充当学习笔记的作用,在书写过程中难免会出现错误以及天真的理论理解,还请各位指正。

我将该项目的实现分成下面几个步骤(每个步骤下的博客会一步一步地更新):

  1. 实现机械臂在ROS1+Gazebo环境下的控制、仿真。目标效果是给出任意坐标的方块,机械臂要能稳定的抓取,并放置到指定的坐标。

该步骤博客目录如下:

https://blog.csdn.net/m0_75114363/article/details/156164226?spm=1001.2014.3001.5501
https://blog.csdn.net/m0_75114363/article/details/156166592?spm=1001.2014.3001.5502
https://blog.csdn.net/m0_75114363/article/details/156426200?spm=1001.2014.3001.5501
https://blog.csdn.net/m0_75114363/article/details/156544524?spm=1001.2014.3001.5502

  1. 加入视觉模块与算法。目标效果是在仿真环境下,对于随意放置的方块,视觉系统需要计算出其真实坐标给予机械臂控制模块,使得机械臂能够实现对其的抓取与放置。

  2. 加入视觉模块与算法。目标效果是在仿真环境下,对于随意放置的方块,视觉系统需要计算出其真实坐标给予机械臂控制模块,使得机械臂能够实现对其的抓取与放置。

该步骤博客目录如下:

  1. 加入LLM(本地部署或使用API)。目标效果是对于输入的任意文本指令,LLM能根据预设的prompt,结合视觉系统给予的信息,给予执行模块对应的动作序列,使得机械臂正确地实现输入的文本指令想达到的效果,实现V-L-A的完整交互。

该步骤博客目录如下:

  1. 实现整体系统的优化与完善,包括基于QT搭建软件前端、优化模型外观、加入更复杂的机械臂、实现更复杂的指令解析与运行。

该步骤博客目录如下:

我所使用的环境如下:

  1. 系统:Ubuntu20.04

  2. ROS1:Noetic

项目地址:

https://github.com/Dukiyaaa/Cmd2Action_ROS1

此外,额外说明一下为什么这个项目会选择ROS1做框架而不是更现代的ROS2。其实我在初期也是用的ROS2的框架,但发现机械臂夹爪始终无法夹起物体,网上相关的机械臂开源资料基本都是基于ROS1的,加上ROS1提供了grasp_fix插件可防止物体掉落,所以最终我选择了ROS1做项目框架,同时也希望自己在后期能够在ROS2上成功迁移项目。


章节概述

在上一篇文章(

https://blog.csdn.net/m0_75114363/article/details/156426200?spm=1001.2014.3001.5502

)的1.1.3,我描述了在抓取物体时存在的一种bug,即在某些情况下夹爪闭合时会刚好夹到物体的棱角,导致无法建立稳定接触,无法夹起物体。

在上一篇中,我给出的解决方法是让四个手指先后闭合,进而推动物体进行位姿矫正。这种办法有一定效果,但在实际仿真中,会出现穿模的情况。今天我使用了新的办法来解决改bug--在gripper_link下新增一个旋转关节,在下降夹爪之前先进行方向对齐,这样便能保证每次闭合夹爪时手指都能与物体良好接触


1. urdf修改

在base.urdf.xacro中,新增了一个旋转关节gripper_roll和一个过渡link gripper_roll_link,四个手指由原先挂载在gripper_link上改为了挂载在gripper_roll_link上

复制代码
        <joint name="gripper_roll" type="revolute">
            <parent link="gripper_link"/>
            <child link="gripper_roll_link"/>
            <origin xyz="0 0 -0.2" rpy="0 0 0"/>
            <axis xyz="0 0 1"/>
            <limit effort="10" velocity="3.0" lower="-3.14" upper="3.14"/>
            <dynamics damping="0.05" friction="0.02"/>
        </joint>

        <link name="gripper_roll_link">
            <collision>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <cylinder length="0.01" radius="0.02"/>
                </geometry>
            </collision>
            <visual>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <cylinder length="0.01" radius="0.02"/>
                </geometry>
                <material name="dark">
                    <color rgba="0.0 0.0 0.0 1.0"/>
                </material>
            </visual>
            <inertial>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <mass value="0.05"/>
                <inertia ixx="1e-4" ixy="0.0" ixz="0.0" iyy="1e-4" iyz="0.0" izz="1e-4"/>
            </inertial>
        </link>
        <gazebo reference="gripper_roll_link">
            <material>Gazebo/Dark</material>
        </gazebo>

在controllers.yaml中给gripper_roll关节添加位置控制器

复制代码
gripper_roll_position_controller:
  type: position_controllers/JointPositionController
  joint: gripper_roll
  pid: {p: 50.0, i: 0.0, d: 2.0}

在robot.ros_control.xacro也进行对应注册

复制代码
<transmission name="gripper_roll_transmission">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="gripper_roll">
                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            </joint>
            <actuator name="gripper_roll_motor">
                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
                <mechanicalReduction>1</mechanicalReduction>
            </actuator>
        </transmission>

别忘了在launch文件中启动这个controller

复制代码
<node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"
        args="joint_state_controller rotation1_position_controller rotation2_position_controller gripper_position_controller gripper_roll_position_controller finger1_position_controller finger2_position_controller finger3_position_controller finger4_position_controller"/>

2.业务逻辑时实现

封装了个align_gripper_roll函数和get_gripper_roll_yaw函数:

复制代码
def align_gripper_roll(self):
        """
        对齐夹爪朝向:获取当前 yaw 角,然后旋转夹爪使其回到初始朝向(相对于世界坐标系为 0)
        """
        yaw = self.get_gripper_roll_yaw()
        if yaw is not None:
            rospy.loginfo("当前 gripper_roll yaw 角: %.3f rad (%.1f 度)" % (yaw, np.degrees(yaw)))
            self.gripper_roll_pub.publish(Float64(-yaw))
            rospy.loginfo("旋转夹爪以对齐初始朝向")
        else:
            rospy.loginfo("无法获取 gripper_roll yaw 角")

def get_gripper_roll_yaw(self):
        """
        获取 gripper_roll_link 在世界坐标系中的 yaw 角(弧度)
        通过正向运动学计算:yaw = rotation1 + rotation2 + gripper_roll
        
        返回:
            float: yaw 角度值(弧度),如果未获取到则返回 None
        """
        if self.current_joint_state is None:
            rospy.logwarn("尚未接收到关节状态信息")
            return None
        
        try:
            # 获取各关节角度
            rotation1_idx = self.current_joint_state.name.index('rotation1')
            rotation2_idx = self.current_joint_state.name.index('rotation2')
            gripper_roll_idx = self.current_joint_state.name.index('gripper_roll')
            
            rotation1 = self.current_joint_state.position[rotation1_idx]
            rotation2 = self.current_joint_state.position[rotation2_idx]
            gripper_roll = self.current_joint_state.position[gripper_roll_idx]
            
            # 计算 gripper_roll_link 的世界 yaw 角
            world_yaw = rotation1 + rotation2 + gripper_roll
            
            return world_yaw
        except ValueError:
            rospy.logwarn("未找到所需关节")
            return None
        except IndexError:
            rospy.logwarn("关节状态数据不完整")
            return None

该函数在下降夹爪前使用,通过get_gripper_roll_yaw函数可以获得机械臂经过ik运动后,gripper_roll相对于世界坐标系的yaw角,我们只需要通过话题发布让gripper_roll关节反方向旋转对应角度,即可让夹爪方向与物体方向对齐。

get_gripper_roll_yaw的原理也很简单,由于rotation1、rotation2、gripprt_roll都是绕z轴转动的,所以gripprt_roll最后相对于世界坐标系的yaw角就是三者转角相加。

在复位时,将夹爪转回初始的状态,这样在下次运行任务时,gripper_roll的转角i才不会弄混:

复制代码
def arm_reset(self):
        """手臂复位到初始位置"""
        rospy.loginfo("手臂复位到初始位置")
        self.move_arm_simple(0.0, 0.0, 0.0, duration=3.0)
        
        # 直接将 gripper_roll 复位到 0
        rospy.loginfo("复位 gripper_roll 到初始角度")
        self.gripper_roll_pub.publish(Float64(0.0))
        rospy.sleep(1.0)
        
        self.open_gripper(duration=1.5)
        rospy.loginfo("手臂复位完成\n")

总结

这篇文章讲了夹爪无法与物体产生良好接触时的新的解决办法。

相关推荐
CoovallyAIHub4 分钟前
YOLOv12之后,AI在火场如何进化?2025最后一篇YOLO论文揭示:要在浓烟中看见关键,仅靠注意力还不够
深度学习·算法·计算机视觉
LDG_AGI20 分钟前
【推荐系统】深度学习训练框架(二十一):DistributedCheckPoint(DCP) — PyTorch分布式模型存储与加载
pytorch·分布式·深度学习
Hcoco_me35 分钟前
大模型面试题41:RoPE改进的核心目标与常见方法
开发语言·人工智能·深度学习·自然语言处理·transformer·word2vec
LDG_AGI37 分钟前
【推荐系统】深度学习训练框架(二十三):TorchRec端到端超大规模模型分布式训练+推理实战
人工智能·分布式·深度学习·机器学习·数据挖掘·推荐算法
Hcoco_me1 小时前
大模型面试题39:KV Cache 完全指南
人工智能·深度学习·自然语言处理·transformer·word2vec
小途软件1 小时前
基于计算机视觉的课堂行为编码研究
人工智能·python·深度学习·计算机视觉·语言模型·自然语言处理·django
盼小辉丶1 小时前
PyTorch实战——pix2pix详解与实现
pytorch·深度学习·生成模型
cyyt1 小时前
深度学习周报(25.12.29~26.1.4)
人工智能·深度学习
万俟淋曦2 小时前
【论文速递】2025年第51周(Dec-14-20)(Robotics/Embodied AI/LLM)
人工智能·深度学习·机器人·大模型·论文·robotics·具身智能
汗流浃背了吧,老弟!2 小时前
基于 BERT 的指令微调
人工智能·深度学习·bert