ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试

URDF(Universal Robot Description Format——通用机器人描述格式)是ROS里使用的一种机器人的描述文件,包含的内容有:连杆、关节,运动学和动力学参数、可视化模型、碰撞检测模型等。简单的机器人模型可以人工编写,但是对于复杂的模型,转动惯量等参数计算复杂,人工编写很费时费力,好在ROS wiki 中提供一款将Solidworks模型转换为URDF文件的插件sw2urdfSetup。最近从淘宝上购买了一款开源的六自由度的机械臂,卖家提供了完整的Solidworks装配图及零件图(如下图示),但是并没有提供该机械臂的ROS驱动,也没有URDF模型,打算自行完成ROS相关驱动支持,并开展基于该机械臂的强化学习控制研究。

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第1张图片

本机械臂看似简单,也包含了近90个零件,其中机械抓部分相对特殊与复杂,因为机械抓虽然包含有6个关节,但是只有一个关节直接受舵机驱动,其余的关节由这个关节联动,sw2urdfSetup插件不能直接处理这种情况,必须对生成的URDF文件进行调整。

本文完成了机械臂机械抓部分的URDF模型建立以及gazebo运动仿真的支持,具体包含以下几个过程:

(1)solidworks中将机械抓部分装配体的建立与调整

这部分工作是将机械抓部分的零件拿出来建立一个单独的装配体,如下:

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第2张图片

然后在装配体内部根据URDF中每个link包含的部分聚合成不同的装配体,各部分如下(依次为base_link、left_knuckle_link、right_knuckle_link、left_inner_knuckle_link、right_inner_knuckle_link、left_finger_link、right_finger_link):

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第3张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第4张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第5张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第6张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第7张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第8张图片ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第9张图片

注意每一个装配体link上要建立坐标系与基准轴(编辑link装配体时菜单操作:插入——参考几何体——基准轴或坐标系),其中基准轴用于选择表示为joint的运动轴,子link的坐标系原点在父link对应的基准轴方向上(一个父link对应几个子link就有几个基准轴),坐标系的一个轴应该与基准轴平行。这些坐标系与基准轴在sw2urdfSetup插件生成URDF文件时需要。

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第10张图片

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第11张图片

基准轴与坐标系应该在link的子装配体中添加,如上面第一幅图示,第二副图是带坐标系与基准轴显示的总的装配体模型,将材料改成了黄铜,所以颜色变了,我这里没有进一步调整了。

(2)基于sw2urdfSetup插件生成机械抓URDF文件

可以参考下面的博客文章和ROS wiki,注意有三个地方需要修改:  

https://blog.csdn.net/gpeng832/article/details/73917487

我这里的版本中实际操作与上面链接中有所不同:加载插件后,插件菜单位置在 工具——file——export as URDF,而不是教程里说的工具栏。

配置每个link,主要是坐标系与基准轴不要搞错了:

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第12张图片

点击 “preview and export”,配置每个关节jiont,主要是配置限制 limit ,一个都不能空,一开始我的 速度与力矩 没有设置,自动生成了零,会导致gazebo中关节没法运动:

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第13张图片

点击 next,大部分都是自动生成:

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第14张图片

最后点完成生成相关文件,保存对话框文件名称中的SolidWorks装配体后缀要去掉。参考下面链接修改三个地方。

 https://blog.csdn.net/gpeng832/article/details/73917487 

生成文件目录如下:

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第15张图片

(3)基于mimic_joint_plugin等在gazebo中实现关节联动控制

SolidWorks插件自动生成的urdf模型不具有关节联动控制的效果,需要进行修改,下面将修改后的源码贴出来。

le_arm_gripper.transmission.xacro:



  
  
  

      
          transmission_interface/SimpleTransmission
          
            PositionJointInterface
          
          	 
            1
            PositionJointInterface
          
      

      
        
            ${prefix}left_knuckle_joint
            ${prefix}right_finger_joint
        

          
            ${prefix}left_knuckle_joint
            ${prefix}right_inner_knuckle_joint
            -1
            0.0
          

          
            ${prefix}left_knuckle_joint
            ${prefix}left_finger_joint
            -1
            0.0	
          
            
            
            ${prefix}left_knuckle_joint
            ${prefix}left_inner_knuckle_joint
          

            
            ${prefix}left_knuckle_joint
            ${prefix}right_knuckle_joint
            -1
            0.0	
            
       
  

le_arm_gripper.xacro:




    
    
    
         
            /
         
    
    
    
    
        
        
        
    

    
        
            
            
                
            
        
        
            
            
                
            
        
        
            
            
            
        
    
    
    
        
    
    

le_arm_gripper.urdf.xacro文件太长,这里给出了部分源码:

           
        
            
            
            
        
        
            
                
                
                
            
            
            
            
                
            
            
                
            
            
            
            
            
                
            
            
        
        
            1
            100000
            100000
            100000000.0
            1.0
         
        
            
            
            
            
            
            
            
            
                
            
            
                
            
            
            
            
            
                
            
            
        

        
            1
            100000
            100000
            100000000.0
            1.0
         

        
            
            
            
            
            
        
        
            
            
            
            
            
            
            
            
                
            
            
                
            
            
            
            
            
                
            
            
        

        
            1
            100000
            100000
            100000000.0
            1.0
         

        
            
            
            
            
            
            
        

另外,要实现关节位置控制,还需要添加相关控制器配置文件:

gripper_controller.yaml 

gripper_controller:
  type: position_controllers/JointTrajectoryController
  joints:
     - left_knuckle_joint
  constraints:
      goal_time: 0.6
      stopped_velocity_tolerance: 0.05
      left_knuckle_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  25
  action_monitor_rate: 10

joint_state_controller.yaml 

joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

启动文件如下:

controller_utils.launch 




  
  
    
    
  

  
  
  
  
  
  
 

upload_le_arm_gripper.launch 


      

le_arm_gripper_gazebo.launch 



  
  
  
  
  
  
    
    
    
  

  
  

  
  

  
   
  

 

(4)效果展示

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第16张图片

执行测试命令为:

rostopic  pub /gripper_controller/command trajectory_msgs/JointTrajectory '{joint_names:["left_knuckle_joint"],points: [{positions:[0.5], time_from_start: [1.0,0.0]}]}' -1

 

ROS开发笔记(11)——Solidworks机械臂模型转化为URDF+mimic关节联动+gazebo中运动控制测试_第17张图片

说明控制指令已经正确执行,这里没有纹理,将mesh文件将stl格式的文件由dae文件替代可以展示出纹理。

下一步将机械臂的其它部分都添加完毕后一同进行moveit的配置。

 

你可能感兴趣的:(ROS开发)