Skip to content
Hancheol Choi edited this page Feb 10, 2018 · 10 revisions

Prerequisites

Overview / HelloWorld Plugin Tutorial

Note: 만약에 이전 튜토리얼에서 계속 하고있다면, 아래 나오는 튜토리얼에 적절한 #include를 넣어줘야 한다.

Code

Source: gazebo/examples/plugins/model_push

플러그인은 모델의 물리적 속성과 기본 요소 (링크, 조인트, 충돌 객체)에 대한 완벽한 접근을 허용한다. 다음 플러그인은 상위 모델에 선속도를 적용한다.

$ cd ~/gazebo_plugin_tutorial
$ gedit model_push.cc

Plugin Code:

#include <functional>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
#include <ignition/math/Vector3.hh>

namespace gazebo
{
  class ModelPush : public ModelPlugin
  {
    public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
    {
      // Store the pointer to the model
      this->model = _parent;

      // Listen to the update event. This event is broadcast every
      // simulation iteration.
      this->updateConnection = event::Events::ConnectWorldUpdateBegin(
          std::bind(&ModelPush::OnUpdate, this));
    }

    // Called by the world update start event
    public: void OnUpdate()
    {
      // Apply a small linear velocity to the model.
      this->model->SetLinearVel(ignition::math::Vector3d(.3, 0, 0));
    }

    // Pointer to the model
    private: physics::ModelPtr model;

    // Pointer to the update event connection
    private: event::ConnectionPtr updateConnection;
  };

  // Register this plugin with the simulator
  GZ_REGISTER_MODEL_PLUGIN(ModelPush)
}

Compiling the Plugin

Hello WorldPlugin tutorial을 해보았다면, ~/gazebo_plugin_tutorial/CMakeLists.txt파일에 아래 행을 추가해야 한

add_library(model_push SHARED model_push.cc)
target_link_libraries(model_push ${GAZEBO_LIBRARIES})

이 코드를 컴파일하면 가제보 시뮬레이션에 삽입할 수 있는 공유 라이브러리 ~/gazebo_plugin_tutorial/build/libmodel_push.so 가 생성된다.

$ cd ~/gazebo_plugin_tutorial/build
$ cmake ../
$ make

Running the Plugin

이 플러그인은 world 파일 examples/plugins/model_push/model_push.world 에서 사용된다.

$ cd ~/gazebo_plugin_tutorial
$ gedit model_push.world
<?xml version="1.0"?> 
<sdf version="1.4">
  <world name="default">

    <!-- Ground Plane -->
    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>

    <model name="box">
      <pose>0 0 0.5 0 0 0</pose>
      <link name="link">
        <collision name="collision">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
        </collision>

        <visual name="visual">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
        </visual>
      </link>

      <plugin name="model_push" filename="libmodel_push.so"/>
    </model>        
  </world>
</sdf>

플러그인을 모델에 부착하는 후크(hook)는 모델 요소의 마지막에 지정된다:

아래 내용은 이번 예제에 해당되는 내용이며, 필요에따라 수정해서 사용해야 함

<plugin name="model_push" filename="libmodel_push.so"/>

라이브러리 경로를 GAZEBO_PLUGIN_PATH에 추가한다:

$ export GAZEBO_PLUGIN_PATH=$HOME/gazebo_plugin_tutorial/build:$GAZEBO_PLUGIN_PATH

시뮬레이션을 시작하고, 실행한다

$ cd ~/gazebo_plugin_tutorial/
$ gzserver -u model_push.world

-u 옵션은 일시 정지된 상태(paused state)로 서버를 시작한다.

별도의 터미널에서 gui를 시작한다

$ gzclient

Table of Contents




Clone this wiki locally