ROS学习笔记11 —— ros联合gazebo仿真(RRBOT案例)

文章目录

  • RRBot栗子
    • 1. transmission
    • 2. gazebo_ros_control插件
    • 3. yaml配置文件
    • 4. 加载yaml的launch文件
    • 5. 使用roslauunch启动控制器和节点
    • 6. 使用rqt发送命令
    • 7. 控制器性能可视化
    • 8. 动态参数配置
    • 9. 保存rqt配置的launch文件
    • 10. 将Rviz连接到Gazebo Simulation

这篇文章可以帮助我们快速了解大概框架

RRBot栗子

文件级如下:


miracle@miracle-robot:~/Desktop/gazebo_ros_demos-kinetic-devel$ tree
.
├── gazebo_tutorials
│   ├── CMakeLists.txt
│   ├── launch
│   │   └── hello.launch
│   ├── package.xml
│   ├── src
│   │   └── simple_world_plugin.cpp
│   └── worlds
│       └── hello.world
├── README.md
├── rrbot_control
│   ├── CMakeLists.txt
│   ├── config
│   │   └── rrbot_control.yaml
│   ├── launch
│   │   ├── rrbot_control.launch
│   │   ├── rrbot_rqt.launch
│   │   └── rrbot_rqt.perspective
│   └── package.xml
├── rrbot_description
│   ├── CMakeLists.txt
│   ├── launch
│   │   ├── rrbot.rviz
│   │   └── rrbot_rviz.launch
│   ├── meshes
│   │   └── hokuyo.dae
│   ├── package.xml
│   └── urdf
│       ├── materials.xacro
│       ├── rrbot.gazebo
│       ├── rrbot.xacro
│       └── rrbot.xml
└── rrbot_gazebo
    ├── CMakeLists.txt
    ├── launch
    │   └── rrbot_world.launch
    ├── package.xml
    └── worlds
        └── rrbot.world

1. transmission

rrbot.xacro

  <transmission name="tran1">
    <type>transmission_interface/SimpleTransmissiontype>
    <joint name="joint1">
      <hardwareInterface>EffortJointInterfacehardwareInterface>
    joint>
    <actuator name="motor1">
      <hardwareInterface>EffortJointInterfacehardwareInterface>
      <mechanicalReduction>1mechanicalReduction>
    actuator>
  transmission>

  <transmission name="tran2">
    <type>transmission_interface/SimpleTransmissiontype>
    <joint name="joint2">
      <hardwareInterface>EffortJointInterfacehardwareInterface>
    joint>
    <actuator name="motor2">
      <hardwareInterface>EffortJointInterfacehardwareInterface>
      <mechanicalReduction>1mechanicalReduction>
    actuator>
  transmission>

2. gazebo_ros_control插件

该插件主要实现gazebo中模型的驱动。

rrbot.gazebo

<gazebo>
  <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <robotNamespace>/myrobotrobotNamespace>
  plugin>
gazebo>

3. yaml配置文件

PID增益和控制器设置必须保存在yaml文件中,在rrbot_control/config目录下,该文件通过roslaunch文件加载到参数服务器中。

rrbot:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  # Position Controllers ---------------------------------------
  joint1_position_controller:
    type: effort_controllers/JointPositionController
    joint: joint1
    pid: {p: 100.0, i: 0.01, d: 10.0}
  joint2_position_controller:
    type: effort_controllers/JointPositionController
    joint: joint2
    pid: {p: 100.0, i: 0.01, d: 10.0}

4. 加载yaml的launch文件

位于rrbot_control/launch目录下

<launch>

  
  <rosparam file="$(find rrbot_control)/config/rrbot_control.yaml" command="load"/>

  
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="screen" ns="/rrbot" args="joint1_position_controller joint2_position_controller joint_state_controller"/>

  
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
    respawn="false" output="screen">
    <remap from="/joint_states" to="/rrbot/joint_states" />
  node>

launch>

5. 使用roslauunch启动控制器和节点

# 启动仿真
roslaunch rrbot_gazebo rrbot_world.launch

# 加载控制器
roslaunch rrbot_control rrbot_control.launch
  • 还可以手动加载控制器:
rosservice call /rrbot/controller_manager/load_controller "name: 'joint1_position_controller'"
rosservice call /rrbot/controller_manager/load_controller "name: 'joint2_position_controller'"
  • 手动启动控制器:
rosservice call /rrbot/controller_manager/switch_controller "{start_controllers: ['joint1_position_controller','joint2_position_controller'], stop_controllers: [], strictness: 2}"
  • 手动停止控制器:
rosservice call /rrbot/controller_manager/switch_controller "{start_controllers: [], stop_controllers: ['joint1_position_controller','joint2_position_controller'], strictness: 2}"

  • 手动发生命令:
rostopic pub -1 /rrbot/joint1_position_controller/command std_msgs/Float64 "data: 1.5"
rostopic pub -1 /rrbot/joint2_position_controller/command std_msgs/Float64 "data: 1.0"

6. 使用rqt发送命令

rosrun rqt_gui rqt_gui

Plugins→Topics→Messahe Publisher:
Topic选择/rrbot/joint1_position_controller/command,Type选择std_msgs/Float64,Freq选择100Hz,然后+

expression栏可修改如下:

# 其中i是代表时间的rqt变量
sin(i/100)


# 或者
sin(i/rate*speed)*diff + offset
# rate:计算频率,应与主题发布者的rate相同,推荐为100
# speed:希望连接启动的速度,从1开始,慢速
# diff:(upper_limit - lower_limit)/2
# offset:upper_limit-diff

7. 控制器性能可视化

Plugins→Visualization→Plot→MatPlot处选择要可视化的数据,如/rrbot/joint1_position_controller/command/data

已知RQT plot插件运行一段时间(>1分钟)后会出现错误,当前解决方案是按插件右上方的蓝色刷新按钮

8. 动态参数配置

Plugins→Configuration→Dynamic Reconfigure→Expand All,查看子选项,以PID控制器为例,则应选择pid选项。

动态参数命令行工具说明:传送门

9. 保存rqt配置的launch文件

<launch>

  
  <node name="rrbot_rqt" pkg="rqt_gui" type="rqt_gui" respawn="false"
	output="screen" args="--perspective-file $(find rrbot_control)/launch/rrbot_rqt.perspective"/>

launch>
roslaunch rrbot_control rrbot_rqt.launch

10. 将Rviz连接到Gazebo Simulation

假设您已经按照rosparamroslaunch文件中的说明启动了joint_state_controller,那么下一步就是启动Rviz

rosrun rviz rviz

Global Options下,将 Fixed Frame 改为world,然后添加RobotModel即可。


参考文献:

  • http://wiki.ros.org/ros_control
  • https://wiki.ros.org/urdf/XML/Transmission
  • https://github.com/ros-controls/ros_control/wiki/joint_limits_interface
  • http://gazebosim.org/tutorials/?tut=ros_control
  • https://github.com/ros-simulation/gazebo_ros_demos
  • https://wiki.ros.org/dynamic_reconfigure
  • http://gazebosim.org/tutorials/?tut=ros_comm

你可能感兴趣的:(▶,机器人操作系统ROS/ROS2)