前言:

这一篇文章里,我们做一个下面的机器人的仿真,既然是教程,那么就从最简单的开始,一步一步深入学习。

上一篇文章中,我们做了一个单自由度机器人的仿真,这里我们增加自由度,变成4个自由度,这样好像足式机器人的四条腿一样,可以通过四条腿将身体支撑起来,模拟一个简易的机器人。

 1.编辑urdf文件

这个文件我们命名为gazebo_demo1.urdf.xacro。这里需要注意的几点主要是关节的扭矩和速度,另外零件的质量和惯性矩阵也非常重要,但是在solidworks里导出urdf文件的时候,软件已经为我们精确的计算好了这些数值,所以根本不需要我们操心,如果你觉的这个机器人的质量等参数不对的话,完全可以在solidworks里面设置好,然后再导出urdf文件,这样质量和惯性矩阵就准确设置好了。

关节扭矩和速度这里通过limit标签进行设置。

如下:

<limit effort="value_of_effort" velocity="value_of_velocity" />

这里的value_of_effort这个数值需要更改成自己想要设置的数值,对于转动关节单位是NM(牛米),对于滑动关节单位是N(牛)。后面的value_of_velocity这个数值代表的是速度,这个数值也可以自己任意设置,对于转动关节单位是弧度每秒,对于滑动关节,单位是米每秒。

<?xml version="1.0" encoding="utf-8"?>
 
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
     Commit Version: 1.5.1-0-g916b5db  Build Version: 1.5.7152.31018
     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
 
<robot
 
  name="gazebo_demo1">
  <gazebo>
 
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
 
      <robotNamespace>/gazebo_demo1</robotNamespace>
 
      <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
 
      <legacyModeNS>true</legacyModeNS>
 
    </plugin>
 
  </gazebo>
 
 
 
  <link
 
    name="base_link">
 
    <inertial>
 
      <origin
 
        xyz="-6.0445212263786E-18 1.39257863414922E-18 -2.20581496680807E-19"
 
        rpy="0 0 0" />
 
      <mass
 
        value="0.468" />
 
      <inertia
 
        ixx="0.0001443"
 
        ixy="-1.53384791846956E-20"
 
        ixz="-1.37563571644961E-21"
 
        iyy="0.0003939"
 
        iyz="-1.29382985829106E-37"
 
        izz="0.0005304" />
 
    </inertial>
 
    <visual>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/base_link.STL" />
 
      </geometry>
 
      <material
 
        name="">
 
        <color
 
          rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
 
      </material>
 
    </visual>
 
    <collision>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/base_link.STL" />
 
      </geometry>
 
    </collision>
 
 
 
  </link>
 
 
 
  <link
 
    name="LF_LINK">
 
    <inertial>
 
      <origin
 
        xyz="0.01 -1.59413400484866E-18 0"
 
        rpy="0 0 0" />
 
      <mass
 
        value="0.0108630528372501" />
 
      <inertia
 
        ixx="1.06775440310417E-07"
 
        ixy="1.20998908503938E-22"
 
        ixz="-1.75453282727152E-23"
 
        iyy="7.38080724035423E-07"
 
        iyz="8.06501097239194E-25"
 
        izz="7.99593444190632E-07" />
 
    </inertial>
 
    <visual>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
 
      </geometry>
 
      <material
 
        name="">
 
        <color
 
          rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
 
      </material>
 
    </visual>
 
    <collision>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
 
      </geometry>
 
    </collision>
 
 
 
  </link>
 
  <joint
 
    name="LF_JOINT"
 
    type="continuous">
 
    <origin
 
      xyz="0.045 0.0325 0"
 
      rpy="1.5708 0 0" />
 
    <parent
 
      link="base_link" />
 
    <child
 
      link="LF_LINK" />
 
    <axis
 
      xyz="0 0 1" />
    <dynamic damping="0.7" friction="0.5" />
 
    <limit effort="0.2" velocity="10" />
 
 
 
  </joint>
 
  <link
 
    name="LB_LINK">
 
    <inertial>
 
      <origin
 
        xyz="0.01 -1.90361538571609E-18 6.93889390390723E-18"
 
        rpy="0 0 0" />
 
      <mass
 
        value="0.0108630528372501" />
 
      <inertia
 
        ixx="1.06775440310417E-07"
 
        ixy="1.10469815160512E-22"
 
        ixz="3.53711447230329E-24"
 
        iyy="7.38080724035424E-07"
 
        iyz="5.37667398159464E-25"
 
        izz="7.99593444190632E-07" />
 
    </inertial>
 
    <visual>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
 
      </geometry>
 
      <material
 
        name="">
 
        <color
 
          rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
 
      </material>
 
    </visual>
 
    <collision>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
 
      </geometry>
 
    </collision>
 
 
 
  </link>
 
  <joint
 
    name="LB_JOINT"
 
    type="continuous">
 
    <origin
 
      xyz="-0.045 0.0325 0"
 
      rpy="1.5708 0 0" />
 
    <parent
 
      link="base_link" />
 
    <child
 
      link="LB_LINK" />
 
    <axis
 
      xyz="0 0 1" />
    <dynamic damping="0.7" friction="0.5" />
    <limit effort="0.2" velocity="10" />
 
 
 
  </joint>
 
  <link
 
    name="RF_LINK">
 
    <inertial>
 
      <origin
 
        xyz="0.01 -1.85843759880028E-18 0"
 
        rpy="0 0 0" />
 
      <mass
 
        value="0.0108630528372501" />
 
      <inertia
 
        ixx="1.06775440310417E-07"
 
        ixy="1.5173510835766E-22"
 
        ixz="-9.00355753711158E-24"
 
        iyy="7.38080724035423E-07"
 
        iyz="-3.49483808803654E-24"
 
        izz="7.99593444190632E-07" />
 
    </inertial>
 
    <visual>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
 
      </geometry>
 
      <material
 
        name="">
 
        <color
 
          rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
 
      </material>
 
    </visual>
 
    <collision>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
 
      </geometry>
 
    </collision>
 
 
 
  </link>
 
  <joint
 
    name="RF_JOINT"
 
    type="continuous">
 
    <origin
 
      xyz="0.045 -0.0325 0"
 
      rpy="1.5708 0 0" />
 
    <parent
 
      link="base_link" />
 
    <child
 
      link="RF_LINK" />
 
    <axis
 
      xyz="0 0 1" />
    <dynamic damping="0.7" friction="0.5" />
    <limit effort="0.2" velocity="10" />
 
    
 
  </joint>
 
  <link
 
    name="RB_LINK">
 
    <inertial>
 
      <origin
 
        xyz="0.01 -1.6227366665734E-18 0"
 
        rpy="0 0 0" />
 
      <mass
 
        value="0.0108630528372501" />
 
      <inertia
 
        ixx="1.06775440310417E-07"
 
        ixy="1.36659023251123E-22"
 
        ixz="1.17764472964423E-23"
 
        iyy="7.38080724035423E-07"
 
        iyz="-1.6130021944784E-24"
 
        izz="7.99593444190632E-07" />
 
    </inertial>
 
    <visual>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
 
      </geometry>
 
      <material
 
        name="">
 
        <color
 
          rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
 
      </material>
 
    </visual>
 
    <collision>
 
      <origin
 
        xyz="0 0 0"
 
        rpy="0 0 0" />
 
      <geometry>
 
        <mesh
 
          filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
 
      </geometry>
 
    </collision>
 
 
 
  </link>
 
  <joint
 
    name="RB_JOINT"
 
    type="continuous">
 
    <origin
 
      xyz="-0.045 -0.0325 0"
 
      rpy="1.5708 0 0" />
 
    <parent
 
      link="base_link" />
 
    <child
 
      link="RB_LINK" />
 
    <axis
 
      xyz="0 0 1" />
    <dynamic damping="0.7" friction="0.5" />
    <limit effort="0.2" velocity="10" />
 
    
 
  </joint>
 
 
 
  <gazebo reference="base_link">
    <mu>0.2</mu>
    <mu2>0.2</mu2>
 
    <material>Gazebo/Black</material>
 
  </gazebo>
 
 
 
  <gazebo reference="LF_LINK">
    <mu1>0.8</mu1>
    <mu2>0.8</mu2>
 
    <material>Gazebo/Black</material>
 
  </gazebo>
 
 
 
  <gazebo reference="LB_LINK">
    <mu1>0.8</mu1>
    <mu2>0.8</mu2>
 
    <material>Gazebo/Black</material>
 
  </gazebo>
 
 
 
  <gazebo reference="RF_LINK">
    <mu1>0.8</mu1>
    <mu2>0.8</mu2>
 
    <material>Gazebo/Black</material>
 
  </gazebo>
 
 
 
  <gazebo reference="RB_LINK">
    <mu1>0.8</mu1>
    <mu2>0.8</mu2>
 
    <material>Gazebo/Black</material>
 
  </gazebo>
 
 
 
  <transmission name="LF_JOINT_trans">
 
    <type>transmission_interface/SimpleTransmission</type>
 
    <joint name="LF_JOINT">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
    </joint>
 
    <actuator name="LF_JOINT_motor">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
      <mechanicalReduction>1</mechanicalReduction>
 
    </actuator>
 
  </transmission>
 
 
 
  <transmission name="LB_JOINT_trans">
 
    <type>transmission_interface/SimpleTransmission</type>
 
    <joint name="LB_JOINT">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
    </joint>
 
    <actuator name="LB_JOINT_motor">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
      <mechanicalReduction>1</mechanicalReduction>
 
    </actuator>
 
  </transmission>
 
 
 
  <transmission name="RF_JOINT_trans">
 
    <type>transmission_interface/SimpleTransmission</type>
 
    <joint name="RF_JOINT">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
    </joint>
 
    <actuator name="RF_JOINT_motor">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
      <mechanicalReduction>1</mechanicalReduction>
 
    </actuator>
 
  </transmission>
 
 
 
  <transmission name="RB_JOINT_trans">
 
    <type>transmission_interface/SimpleTransmission</type>
 
    <joint name="RB_JOINT">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
    </joint>
 
    <actuator name="RB_JOINT_motor">
 
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 
      <mechanicalReduction>1</mechanicalReduction>
 
    </actuator>
 
  </transmission>
 
 
 
 
 
 
 
</robot>

2.编辑yaml文件

文件名为:joint_names_gazebo_demo1.yaml

这里的话,一定要注意调好PID参数,如果PID参数设置不对的话,关节轻则颤动,重则乱动,根本不受控制,所以如果gazebo软件一加载进去模型,还没有运行控制程序模型就在乱动,一般情况就是PID参数设置有问题(还有可能就是惯性矩阵设置有问题,不过如果是solidworks软件的插件导出来的话,是非常精确没有问题的),重新调整PID参数之后再次载入试试,一直等到载入模型之后关节不乱动为止。

完整的yaml文件内容如下:

gazebo_demo1:
 
 
 
  # Publish all joint states -----------------------------------
 
 
 
  joint_state_controller:
 
 
 
    type: joint_state_controller/JointStateController
 
 
 
    publish_rate: 50  
 
 
 
 
 
 
 
  # Position Controllers ---------------------------------------
 
 
 
  lf_position_con:
 
 
 
    type: position_controllers/JointPositionController
 
 
 
    joint: LF_JOINT
 
 
 
    #pid: {p: 1.0, i: 0.01, d: 0.0}
 
 
 
  lb_position_con:
 
 
 
    type: position_controllers/JointPositionController
 
 
 
    joint: LB_JOINT
 
 
 
    #pid: {p: 1.0, i: 0.01, d: 0.0}
 
 
 
  rf_position_con:
 
 
 
    type: position_controllers/JointPositionController
 
 
 
    joint: RF_JOINT
 
 
 
    #pid: {p: 1.0, i: 0.01, d: 0.0}
 
 
 
  rb_position_con:
 
 
 
    type: position_controllers/JointPositionController
 
 
 
    joint: RB_JOINT
 
 
 
    #pid: {p: 1.0, i: 0.01, d: 0.0}
 
 
 
 
 
 
 
gazebo_demo1/gazebo_ros_control/pid_gains:
 
  LF_JOINT: {p: 1.0, i: 0.0, d: 0.0}
 
  LB_JOINT: {p: 1.0, i: 0.0, d: 0.0}
 
  RF_JOINT: {p: 1.0, i: 0.0, d: 0.0}
 
  RB_JOINT: {p: 1.0, i: 0.0, d: 0.0}

3.编辑launch启动文件

这里的launch文件名为:gazebo.launch。

launch文件主要需要注意的是载入的关节控制器名称,要把所有的关节控制器全部载入。

完整的launch文件内容如下:

<launch>
 
 
 
  <param name="robot_description" command="$(find xacro)/xacro $(find gazebo_demo1)/urdf/gazebo_demo1.urdf.xacro" />
 
 
 
  <!-- these are the arguments you can pass this launch file, for example paused:=true -->
 
  <arg name="paused" default="false"/>
 
  <arg name="use_sim_time" default="true"/>
 
  <arg name="gui" default="true"/>
 
  <arg name="headless" default="false"/>
 
  <arg name="debug" default="false"/>
 
 
 
  <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
 
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
 
    <arg name="world_name" value="$(find gazebo_demo1)/worlds/gazebo_demo1.world"/>
 
    <arg name="debug" value="$(arg debug)" />
 
    <arg name="gui" value="$(arg gui)" />
 
    <arg name="paused" value="$(arg paused)"/>
 
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
 
    <arg name="headless" value="$(arg headless)"/>
 
  </include>
 
 
 
 
 
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
 
    args="-urdf -model myrobot -param robot_description"/>
 
 
 
 
 
  <rosparam file="$(find gazebo_demo1)/config/joint_names_gazebo_demo1.yaml" command="load"/>
 
 
 
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
 
	output="screen" ns="/gazebo_demo1" args="lf_position_con
                                                 lb_position_con
                                                 rf_position_con
                                                 rb_position_con
"/>
 
 
 
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
 
	respawn="false" output="screen">
 
    <remap from="/joint_states" to="/gazebo_demo1/joint_states" />
 
  </node>
 
 
 
 
 
 
 
</launch>

一般来说在编辑好了launch文件之后,就可以直接运行launch文件启动gazebo查看模型了,如果模型一切正常,那么我们可以运行接下来的控制程序对关节进行控制,如果不正常的话,我们继续修改以上的参数(具体修改哪些参数上面已经给出,不再重复)。

打开模型看看:

4.编写cpp控制程序

编写cpp控制程序,我们的cpp文件名为:gazebo_demo1.cpp。

这里的cpp文件主要是向ros_control发布的每个关节控制器对应的command话题上发布关节位置消息,当我们发布关节位置消息之后,就可以看到gazebo软件里面机器人模型的相应的关节运行到了我们发布的位置。

cpp完整程序如下:

#include "ros/ros.h"
#include "std_msgs/Float64.h" 
#include <sstream>
 
int main(int argc, char  *argv[])
{   
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"control_gazebo_demo1");
    ros::NodeHandle nh;
    ros::Publisher pub_lf = nh.advertise<std_msgs::Float64>("/gazebo_demo1/lf_position_con/command",10);
    ros::Publisher pub_lb = nh.advertise<std_msgs::Float64>("/gazebo_demo1/lb_position_con/command",10);
    ros::Publisher pub_rf = nh.advertise<std_msgs::Float64>("/gazebo_demo1/rf_position_con/command",10);
    ros::Publisher pub_rb = nh.advertise<std_msgs::Float64>("/gazebo_demo1/rb_position_con/command",10);
    std_msgs::Float64 control_gazebo_demo1;
    control_gazebo_demo1.data=0.0;
    bool flag=0;//0weizeng 1weijian
    ros::Rate r(15);
    while (ros::ok())
    {
 
        pub_lf.publish(control_gazebo_demo1);
        pub_lb.publish(control_gazebo_demo1);
        pub_rf.publish(control_gazebo_demo1);
        pub_rb.publish(control_gazebo_demo1);
        control_gazebo_demo1.data+=0.1;
        r.sleep();
        
        ros::spinOnce();
    }
    return 0;
}

5.运行效果

我们把第四步里面的程序编译运行,然后查看效果:

Gazebo仿真例程——4自由度关节

可以看到,机器人已经动起来了,地面有点滑,导致会有滑动,接下来再修改参数试试。

6.完整功能包源码

完整的功能包源码在这里:

https://gitee.com/li9535/gazebo_simulation_ros_package