Gazebo插件通过标准C++类直接控制Gazebo模型, 其具有以下优点
可以控制gazebo中几乎各个方面;
容易共享;
能够在运行的系统中插入移除;
Gazebo插件共有六种:
1.World:控制世界特性,如物理引擎、环境光等
2.Model:用于控制关节和模型状态
3.Sensor:用于获取传感器数据和控制传感器
4.System
5.Visual
6.GUI
Plugin简单例程---Hello WorldPlugin!
安装Gazebo开发文件
sudo apt-get install libgazebo#-dev //#为gazebo版本号,6、7 .etc
创建Plugin文件夹
mkdir ~/gazebo_plugin_tutorial
cd ~/gazebo_plugin_tutorial
gedit hello_world.cc
输入如下代码:
#include
/* 包含gazebo基本功能,
不包括gazebo/physics/physics.hh, gazebo/rendering/rendering.hh, 和 gazebo/sensors/sensors.hh */
namespace gazebo //所有插件都需要在gazebo名空间中编写
{
/* 所有插件类的创建需要继承一种plugin类型,下面是继承WorldPlugin */
class WorldPluginTutorial : public WorldPlugin
{
public: WorldPluginTutorial() : WorldPlugin()//默认构造函数
{
printf("Hello World!\n");//只要创建该类类型就会打印
}
/* 唯一另一个必须的函数是Load(),其中_sdf接收一个包含sdf文件中指定的参数和属性 */
public: void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
{
}
};
/* 使用GZ_REGISTER_WORLD_PLUGIN macro函数将插件注册,函数的需要的参数仅为插件类名
macro函数还包括GZ_REGISTER_MODEL_PLUGIN, GZ_REGISTER_SENSOR_PLUGIN, GZ_REGISTER_GUI_PLUGIN,
GZ_REGISTER_SYSTEM_PLUGIN and GZ_REGISTER_VISUAL_PLUGIN*/
GZ_REGISTER_WORLD_PLUGIN(WorldPluginTutorial)
}
编译plugin代码---创建CMakeLists.txt
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
find_package(gazebo REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS})
list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
add_library(hello_world SHARED hello_world.cc)
target_link_libraries(hello_world ${GAZEBO_LIBRARIES})
编译CMakeLists
mkdir ~/gazebo_plugin_tutorial/build
cd ~/gazebo_plugin_tutorial/build
cmake ../
make
编译后即可生成如下图所示共享库文件
将库路径添加到GAZEBO_PLUGIN_PATH
export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:~/gazebo_plugin_tutorial/build
使用插件
只要作为共享库编译插件,就可以将其添加到SDF文件的world或model中。gazebo会分析sdf文件,定位插件,加载插件代码。为了让gazebo找到插件,可以填写插件绝对路径或将插件路径添加到GAZEBO_PLUGIN_PATH环境变量中。
创建world文件
gedit ~/gazebo_plugin_tutorial/hello.world
在world文件中添加plugin插件
运行world文件
gzserver ~/gazebo_plugin_tutorial/hello.world --verbose
本插件会向当前模型施加一个线速度。记得测试之前先把上一个教程的代码删除,重新编写合适的CMakeLists进行编译
$ cd ~/gazebo_plugin_tutorial
$ gedit model_push.cc
插件代码
#include ///STL 定义运算函数(代替运算符)
#include
#include
#include
#include
namespace gazebo
{
class ModelPush : public ModelPlugin
{
/* typedef boost::shared_ptr ModelPtr Model类型的共享指针
sdf::ElementPtr指向sdf,即将.world文件中的参数属性导入进来*/
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
{
/* Store the pointer to the model
让ModelPush中的model指向当前模型*/
this->model = _parent;
/* Listen to the update event. This event is broadcast every
simulation iteration循环.
typedef boost::shared_ptr ConnectionPtr
static ConnectionPtr ConnectWorldUpdateBegin(T _subscriber) */
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
std::bind(&ModelPush::OnUpdate, this));//std::bind在functional中
}
// Called by the world update start event
public: void OnUpdate()
{
// Apply a small linear velocity to the model.
// void SetLinearVel(const math::Vector3 & _vel)
//model是指向physics中的Model类的智能指针,因此要在API中model class中找SetLinearVel
this->model->SetLinearVel(ignition::math::Vector3d(.3, 0, 0));
}
// Pointer to the model
private: physics::ModelPtr model;
/* Pointer to the update event connection
typedef boost::shared_ptr ConnectionPtr*/
private: event::ConnectionPtr updateConnection;
};
// 注册插件
GZ_REGISTER_MODEL_PLUGIN(ModelPush)
}
编译插件,改写~/gazebo_plugin_tutorial/CMakeLists.txt后保存
add_library(model_push SHARED model_push.cc)
target_link_libraries(model_push ${GAZEBO_LIBRARIES})
编译
$ cd ~/gazebo_plugin_tutorial/build
$ cmake ../
$ make
运行插件,在.world环境文件中添加插件
~/gazebo_plugin_tutorial/model_push.world
$ cd ~/gazebo_plugin_tutorial
$ gedit model_push.world
环境文件内容如下:
model://ground_plane
model://sun
0 0 0.5 0 0 0
1 1 1
1 1 1
将库文件添加到环境变量中
$ export GAZEBO_PLUGIN_PATH=$HOME/gazebo_plugin_tutorial/build:$GAZEBO_PLUGIN_PATH
运行环境
$ cd ~/gazebo_plugin_tutorial/
$ gzserver -u model_push.world
打开图形界面并点击Play
$ gzclient
可以看到箱子会被一个力向前推