ROS2与Gazebo11入门教程-系统插件
说明:
- 介绍系统插件
概述
源代码可以在资源 gazebo/examples/plugins/system_gui_plugin中找到。
本节教程将会创建一个源文件,该文件是gzclient的一个系统插件,旨在将图像保存到/tmp/gazebo_frames目录中。
源代码
- 这里从源文件开始。创建一个名为http://system_gui.cc的文件,命令为:
$ cd ~/gazebo_plugin_tutorial
$ gedit http://system_gui.cc
- 将以下代码内容复制到http://system_gui.cc文件中:
#include <functional>
#include <gazebo/gui/GuiIface.hh>
#include <gazebo/rendering/rendering.hh>
#include <gazebo/gazebo.hh>
namespace gazebo
{
class SystemGUI : public SystemPlugin
{
/////////////////////////////////////////////
/// \brief Destructor
public: virtual ~SystemGUI()
{
this->connections.clear();
if (this->userCam)
this->userCam->EnableSaveFrame(false);
this->userCam.reset();
}
/////////////////////////////////////////////
/// \brief Called after the plugin has been constructed.
public: void Load(int /*_argc*/, char ** /*_argv*/)
{
this->connections.push_back(
event::Events::ConnectPreRender(
std::bind(&SystemGUI::Update, this)));
}
/////////////////////////////////////////////
// \brief Called once after Load
private: void Init()
{
}
/////////////////////////////////////////////
/// \brief Called every PreRender event. See the Load function.
private: void Update()
{
if (!this->userCam)
{
// Get a pointer to the active user camera
this->userCam = gui::get_active_camera();
// Enable saving frames
this->userCam->EnableSaveFrame(true);
// Specify the path to save frames into
this->userCam->SetSaveFramePathname("/tmp/gazebo_frames");
}
// Get scene pointer
rendering::ScenePtr scene = rendering::get_scene();
// Wait until the scene is initialized.
if (!scene || !scene->Initialized())
return;
// Look for a specific visual by name.
if (scene->GetVisual("ground_plane"))
std::cout << "Has ground plane visual\n";
}
/// Pointer the user camera.
private: rendering::UserCameraPtr userCam;
/// All the event connections.
private: std::vector<event::ConnectionPtr> connections;
};
// Register this plugin with the simulator
GZ_REGISTER_SYSTEM_PLUGIN(SystemGUI)
}
函数Load和Init均不得阻塞。在启动并在加载Gazebo之前,会先调用Load和Init函数。
在第一个Update函数中,获取了一个指向用户相机(图形界面中使用的相机)的指针,并启用了帧保存功能。
获取用户相机:
this->userCam = gui::get_active_camera();
- 启用帧保存功能:
this->userCam->EnableSaveFrame(true);
- 设置保存帧的位置(路径名):
this->userCam->SetSaveFramePathname("/tmp/gazebo_frames");
编译相机插件
- 假设读者已经阅读了Hello WorldPlugin教程,则所有要做的就是将以下两行添加到〜/gazebo_plugin_tutorial/CMakeLists.txt文件中:
add_library(system_gui SHARED http://system_gui.cc)
target_link_libraries(system_gui ${GAZEBO_LIBRARIES})
- 再次构建(编译),这样应该会生成一个libsystem_gui.so共享库。
$ cd ~/gazebo_plugin_tutorial/build
$ cmake ../
$ make
运行插件
- 首先启动后台服务器gzserver:
$ gzserver &
- 然后用插件运行客户端gzclient:
$ gzclient -g libsystem_gui.so
这样就应该可以在/tmp/gazebo_frames目录中看到从当前插件中保存的许多图像。
注意:请记住,在退出客户端后,还要终止后台服务器进程。 在同一个终端中,将后台进程带到前台:
$ fg
- 并按下Ctrl + C组合键来终止服务器进程。或者只是关闭gzserver进程,命令为:
$ killall gzserver
参考:
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号