Model plugins - modulabs/gazebo-tutorial GitHub Wiki
Overview / HelloWorld Plugin Tutorial
Note: ๋ง์ฝ์ ์ด์ ํํ ๋ฆฌ์ผ์์ ๊ณ์ ํ๊ณ ์๋ค๋ฉด, ์๋ ๋์ค๋ ํํ ๋ฆฌ์ผ์ ์ ์ ํ
#include๋ฅผ ๋ฃ์ด์ค์ผ ํ๋ค.
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)
}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
์ด ํ๋ฌ๊ทธ์ธ์ 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