ROS2与Gazebo11入门教程-自定义消息
说明:
- 介绍如何创建自定义消息,以及如何在Gazebo插件中订阅和发布这些自定义消息
简介
Gazebo话题通过Google protobuf消息进行通信。Gazebo提供了一系列消息类型(其列表参见此页面),可用于订阅和发布Gazebo话题。
但是,在许多情况下,用户可能希望构建自己的消息类型。
关于本示例代码
本示例项目最终应该会有一个可以创建Gazebo仿真世界2D碰撞地图的插件。该插件将会在Gazebo中栅格化一个仿真世界,并使用RayShape在该网格下进行射线交叉。该插件会将创建的图像发布到一个自定义话题并将其输出到一个图像文件中。该插件的源代码位于GitHub网站上。
请随时为该插件提交问题或拉取请求以对其进行改进。该代码的原创作者是Stephen Brawner。
可以使用git下载该插件源代码:
git clone https://github.com/osrf/collision_map_creator_plugin
- 或者按照下面的说明将代码复制粘贴到文件中。
编写您自己的消息
如果很难将订阅者/发布者消息归属于Gazebo提供的任何一个预定义消息类型,则编写自己的消息就会很有用。而且,可以组合许多不同的消息类型来编写复杂的消息。Gazebo已经包含一个消息库。 对于debian安装,可以在/usr/include/gazebo-11/gazebo/msgs/proto中找到已安装的消息。本节教程将会使用vector2d.proto消息。
通过查看~/collision_map_creator_plugin/msgs/collision_map_ request.proto,可以看出如何声明自定义消息。
package collision_map_creator_msgs.msgs;
import "vector2d.proto";
message CollisionMapRequest
{
required gazebo.msgs.Vector2d upperLeft = 1;
required gazebo.msgs.Vector2d upperRight = 2;
required gazebo.msgs.Vector2d lowerRight = 3;
required gazebo.msgs.Vector2d lowerLeft = 4;
required double height = 5;
required double resolution = 6;
optional string filename = 7 [default = ""];
optional int32 threshold = 8 [default = 255];
}
代码说明
- 首先,用package声明来声明消息所在的命名空间。
package collision_map_creator_msgs.msgs;
- 这里要使用Gazebo的vector2d,因此必须导入和包含该消息(会在CMakeLists.txt文件中指定该消息的位置)。
import "vector2d.proto";
- 该消息的实际构造代码如下:
message CollisionMapRequest
{
}
- 用下面的模板代码或语法来声明消息的每个字段:
["optional"/"required"] [field type] [field name] = [enum];
- 每个枚举(enum)必须是一个唯一的数字。还请注意,必须使用完整的软件包名称来指定外部消息(本示例中的gazebo.msgs)。
required gazebo.msgs.Vector2d upperLeft = 1;
required gazebo.msgs.Vector2d upperRight = 2;
required gazebo.msgs.Vector2d lowerRight = 3;
required gazebo.msgs.Vector2d lowerLeft = 4;
required double height = 5;
required double resolution = 6;
- 消息可以包含可选字段。如果未指定字段值,则可选字段可以包含默认值。下面是声明可选字段默认值的示例:
optional string filename = 7 [default = ""];
optional int32 threshold = 8 [default = 255];
自定义消息的CMakeLists
- 本节教程也提供了~/collision_map_creator/msgs/CMakeLists.txt文件,该文件会根据您的protobuf消息定义生成C ++代码:
代码说明
- 告知CMake包含Protobuf包:
find_package(Protobuf REQUIRED)
- 本部分代码会查找消息的安装位置。对于debian安装,消息文件存储在/usr/include/gazebo-11/gazebo/msgs/proto目录中,但是用户也有可能安装在其他位置。该代码会搜索gazebo-11.X文件夹,并相应设置PROTOBUF_IMPORT_DIRS环境变量,该环境变量用于指定额外消息文件的位置。
set(PROTOBUF_IMPORT_DIRS)
foreach(ITR ${GAZEBO_INCLUDE_DIRS})
if(ITR MATCHES ".*gazebo-[0-11.]+$")
set(PROTOBUF_IMPORT_DIRS "${ITR}/gazebo/msgs/proto")
endif()
endforeach()
- 创建一个名为msgs的列表,其中包含vector2d.proto消息、其依赖项time.proto和header.proto以及collision_map_request.proto消息。
set (msgs
collision_map_request.proto
${PROTOBUF_IMPORT_DIRS}/vector2d.proto
${PROTOBUF_IMPORT_DIRS}/header.proto
${PROTOBUF_IMPORT_DIRS}/time.proto
)
- 为这些消息构建必要的C ++头文件和源代码文件。
PROTOBUF_GENERATE_CPP(PROTO_SRCS PROTO_HDRS ${msgs})
- 添加此消息库,以便可以从其他项目链接到它。库名称必须与下面其他CMakeLists.txt文件中指定的库名称相同。
add_library(collision_map_creator_msgs SHARED ${PROTO_SRCS})
target_link_libraries(collision_map_creator_msgs ${PROTOBUF_LIBRARY})
碰撞地图创建者(Collision Map Creator)插件
- 下面是Gazebo自定义仿真世界插件的完整源代码(该源代码文件为~/collision_map_creator_plugin/http://collision_map_creator.cc):
#include <iostream>
#include <math.h>
// See https://github.com/ignf/gilviewer/issues/8
#define png_infopp_NULL (png_infopp)NULL
#define int_p_NULL (int*)NULL
#define png_bytep_NULL (png_bytep)NULL
#include <boost/gil/gil_all.hpp>
#include <boost/gil/extension/io/png_dynamic_io.hpp>
#include <boost/shared_ptr.hpp>
#include <sdf/sdf.hh>
#include <ignition/math/Vector3.hh>
#include "gazebo/gazebo.hh"
#include "gazebo/common/common.hh"
#include "gazebo/msgs/msgs.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/transport/transport.hh"
#include "collision_map_request.pb.h"
namespace gazebo
{
typedef const boost::shared_ptr<
const collision_map_creator_msgs::msgs::CollisionMapRequest>
CollisionMapRequestPtr;
class CollisionMapCreator : public WorldPlugin
{
transport::NodePtr node;
transport::PublisherPtr imagePub;
transport::SubscriberPtr commandSubscriber;
physics::WorldPtr world;
public: void Load(physics::WorldPtr _parent, sdf::ElementPtr _sdf)
{
node = transport::NodePtr(new transport::Node());
world = _parent;
// Initialize the node with the world name
#if GAZEBO_MAJOR_VERSION >= 8
node->Init(world->Name());
#else
node->Init(world->GetName());
#endif
std::cout << "Subscribing to: " << "~/collision_map/command" << std::endl;
commandSubscriber = node->Subscribe("~/collision_map/command",
&CollisionMapCreator::create, this);
imagePub = node->Advertise<msgs::Image>("~/collision_map/image");
}
public: void create(CollisionMapRequestPtr &msg)
{
std::cout << "Received message" << std::endl;
std::cout << "Creating collision map with corners at (" <<
msg->upperleft().x() << ", " << msg->upperleft().y() << "), (" <<
msg->upperright().x() << ", " << msg->upperright().y() << "), (" <<
msg->lowerright().x() << ", " << msg->lowerright().y() << "), (" <<
msg->lowerleft().x() << ", " << msg->lowerleft().y() <<
") with collision projected from z = " <<
msg->height() << "\nResolution = " << msg->resolution() << " m\n" <<
"Occupied spaces will be filled with: " << msg->threshold() <<
std::endl;
double dX_vertical = msg->upperleft().x() - msg->lowerleft().x();
double dY_vertical = msg->upperleft().y() - msg->lowerleft().y();
double mag_vertical =
sqrt(dX_vertical * dX_vertical + dY_vertical * dY_vertical);
dX_vertical = msg->resolution() * dX_vertical / mag_vertical;
dY_vertical = msg->resolution() * dY_vertical / mag_vertical;
double dX_horizontal = msg->upperright().x() - msg->upperleft().x();
double dY_horizontal = msg->upperright().y() - msg->upperleft().y();
double mag_horizontal =
sqrt(dX_horizontal * dX_horizontal + dY_horizontal * dY_horizontal);
dX_horizontal = msg->resolution() * dX_horizontal / mag_horizontal;
dY_horizontal = msg->resolution() * dY_horizontal / mag_horizontal;
int count_vertical = mag_vertical / msg->resolution();
int count_horizontal = mag_horizontal / msg->resolution();
if (count_vertical == 0 || count_horizontal == 0)
{
std::cout << "Image has a zero dimensions, check coordinates"
<< std::endl;
return;
}
double x,y;
boost::gil::gray8_pixel_t fill(255-msg->threshold());
boost::gil::gray8_pixel_t blank(255);
boost::gil::gray8_image_t image(count_horizontal, count_vertical);
double dist;
std::string entityName;
ignition::math::Vector3d start, end;
start.Z(msg->height());
end.Z(0.001);
#if GAZEBO_MAJOR_VERSION >= 8
gazebo::physics::PhysicsEnginePtr engine = world->Physics();
#else
gazebo::physics::PhysicsEnginePtr engine = world->GetPhysicsEngine();
#endif
engine->InitForThread();
gazebo::physics::RayShapePtr ray =
boost::dynamic_pointer_cast<gazebo::physics::RayShape>(
engine->CreateShape("ray", gazebo::physics::CollisionPtr()));
std::cout << "Rasterizing model and checking collisions" << std::endl;
boost::gil::fill_pixels(image._view, blank);
for (int i = 0; i < count_vertical; ++i)
{
std::cout << "Percent complete: " << i * 100.0 / count_vertical
<< std::endl;
x = i * dX_vertical + msg->lowerleft().x();
y = i * dY_vertical + msg->lowerleft().y();
for (int j = 0; j < count_horizontal; ++j)
{
x += dX_horizontal;
y += dY_horizontal;
start.X(x);
end.X(x);
start.Y(y);
end.Y(y);
ray->SetPoints(start, end);
ray->GetIntersection(dist, entityName);
if (!entityName.empty())
{
image._view(i,j) = fill;
}
}
}
std::cout << "Completed calculations, writing to image" << std::endl;
if (!msg->filename().empty())
{
boost::gil::gray8_view_t view = image._view;
boost::gil::png_write_view(msg->filename(), view);
}
}
};
// Register this plugin with the simulator
GZ_REGISTER_WORLD_PLUGIN(CollisionMapCreator)
}
代码说明
- 首先是包含必要的系统头文件:
#include <iostream>
#include <math.h>
#include <boost/shared_ptr.hpp>
- 而下面这些是该插件所需的Gazebo头文件:
#include "gazebo/gazebo.hh"
#include "gazebo/common/common.hh"
#include "gazebo/math/Vector3.hh"
#include "gazebo/msgs/msgs.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/transport/transport.hh"
为了利用自定义的collision_map_request消息,需要包含其生成的头文件。
#include "collision_map_request.pb.h"
下面这两个头文件是用于写入.png文件所需的:
#include <boost/gil/gil_all.hpp>
#include <boost/gil/extension/io/png_dynamic_io.hpp>
该插件存活于gazebo命名空间中:
namespace gazebo
{
- 下面这个是将被发送给回调方法的对象。为该对象创建一个typedef会很方便:
typedef const boost::shared_ptr<const collision_map_creator_msgs::msgs::CollisionMapRequest> CollisionMapRequestPtr;
- 创建Gazebo仿真世界插件WorldPlugin类的一个派生类。该派生类需要拥有NodePtr,PublisherPtr,SubcriberPtr和WorldPtr,因此必须将它们添加为类变量:
class CollisionMapCreator : public WorldPlugin
{
transport::NodePtr node;
transport::PublisherPtr imagePub;
transport::SubscriberPtr commandSubscriber;
physics::WorldPtr world;
- 然后是定义仿真世界插件的Load方法,该方法会设置节点、仿真世界、订阅者和发布者。
public: void Load(physics::WorldPtr _parent, sdf::ElementPtr _sdf)
{
node = transport::NodePtr(new transport::Node());
world = _parent;
// Initialize the node with the world name
node->Init(world->GetName());
std::cout << "Subscribing to: " << "~/collision_map/command" << std::endl;
- 用该话题、回调函数和指向此插件对象的指针作为参数调用node->Subscribe方法。方法node-> Advertise需要消息类型的一个模板参数和一个要发布的话题名称参数。
commandSubscriber = node->Subscribe("~/collision_map/command", &CollisionMapCreator::create, this);
imagePub = node->Advertise<msgs::Image>("~/collision_map/image");
- 下面这个就是回调方法。该回调方法包含前面使用过的typedef对象。向该回调方法传递了一个引用,因此请确保使用&msg。
public: void create(CollisionMapRequestPtr &msg)
- 对象CollisionMapRequestPtr是一个boost shared_ptr,因此要获取实际字段,需要使用结构解引用('->')而不是结构引用('.')运算符,如下所示。要获取对象的字段,需要调用其获取函数(例如field())。
double z = msg->height();
- 但是请稍等,为什么可以直接引用子字段?那是因为它们不是内部的shared_ptrs,而向我们发送的消息则是内部的shared_ptrs。
double dX_vertical = msg->upperleft().x() - msg->lowerleft().x();
double dY_vertical = msg->upperleft().y() - msg->lowerleft().y();
double mag_vertical = sqrt(dX_vertical * dX_vertical + dY_vertical * dY_vertical);
dX_vertical = msg->resolution() * dX_vertical / mag_vertical;
dY_vertical = msg->resolution() * dY_vertical / mag_vertical;
- 这是如何调用使用过的物理引擎进行单个射线跟踪的示例。这段代码是从gazebo :: physics :: World :: GetEntityBelowPoint(Vector3)中提取出来的:
gazebo::physics::PhysicsEnginePtr engine = world->GetPhysicsEngine();
engine->InitForThread();
gazebo::physics::RayShapePtr ray = boost::dynamic_pointer_cast<gazebo::physics::RayShape>(
engine->CreateShape("ray", gazebo::physics::CollisionPtr()));
- 在格网上进行栅格化以确定哪里有物体,哪里没有物体。
for (int i = 0; i < count_vertical; ++i)
{
...
for (int j = 0; j < count_horizontal; ++j)
{
...
}
...
}
- 这会创建一个图像msg并填充必要的字段。请注意,每个字段的setter方法其格式都类似于set_field(something):
msgs::Image image;
image.set_width(count_horizontal);
image.set_height(count_vertical);
image.set_pixel_format(0);
image.set_step(count_horizontal);
image.set_data(data);
imagePub->Publish(image);
- 最后用仿真程序注册该插件:
// Register this plugin with the simulator
GZ_REGISTER_WORLD_PLUGIN(CollisionMapCreator)
}
请求发布者(Request Publisher)可执行文件
- 该可执行文件位于gazebo之外,但是可以用于说明如何从Gazebo提取所需的库以及如何将自定义的内置消息类型发布到gazebo话题上。这里还有一些必须采取的额外步骤,这些步骤在插件教程中并没有予以说明。可以通过打开〜/collision_map_creator_plugin/request_ http://publisher.cc文件来查看其完整的源代码:
#include <iostream>
#include <math.h>
#include <deque>
#include <sdf/sdf.hh>
#include "gazebo/gazebo.hh"
#include "gazebo/common/common.hh"
#include "gazebo/transport/transport.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/msgs/msgs.hh"
#include "collision_map_request.pb.h"
#include "vector2d.pb.h"
using namespace std;
bool createVectorArray(const char * vectorString,
deque<gazebo::msgs::Vector2d*> corners)
{
deque<gazebo::msgs::Vector2d*>::iterator it;
string cornersStr = vectorString;
size_t opening=0;
size_t closing=0;
for (it = corners.begin(); it != corners.end(); ++it)
{
opening = cornersStr.find('(', closing);
closing = cornersStr.find(')', opening);
if (opening == string::npos || closing == string::npos)
{
std::cout << "Poorly formed string: " << cornersStr << std::endl;
std::cout << "( found at: " << opening << " ) found at: " << closing << std::endl;
return false;
}
string oneCornerStr = cornersStr.substr(opening + 1, closing - opening - 1);
size_t commaLoc = oneCornerStr.find(",");
string x = oneCornerStr.substr(0,commaLoc);
string y = oneCornerStr.substr(commaLoc + 1, oneCornerStr.length() - commaLoc);
(*it)->set_x(atof(x.c_str()));
(*it)->set_y(atof(y.c_str()));
}
return true;
}
int main(int argc, char * argv[])
{
if (argc > 4)
{
collision_map_creator_msgs::msgs::CollisionMapRequest request;
deque<gazebo::msgs::Vector2d*> corners;
corners.push_back(request.mutable_upperleft());
corners.push_back(request.mutable_upperright());
corners.push_back(request.mutable_lowerright());
corners.push_back(request.mutable_lowerleft());
if (!createVectorArray(argv[1],corners))
{
return -1;
}
request.set_height(atof(argv[2]));
request.set_resolution(atof(argv[3]));
request.set_filename(argv[4]);
if (argc == 6)
{
request.set_threshold(atoi(argv[5]));
}
gazebo::transport::init();
gazebo::transport::run();
gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init("default");
std::cout << "Request: " <<
" UL.x: " << request.upperleft().x() <<
" UL.y: " << request.upperleft().y() <<
" UR.x: " << request.upperright().x() <<
" UR.y: " << request.upperright().y() <<
" LR.x: " << request.lowerright().x() <<
" LR.y: " << request.lowerright().y() <<
" LL.x: " << request.lowerleft().x() <<
" LL.y: " << request.lowerleft().y() <<
" Height: " << request.height() <<
" Resolution: " << request.resolution() <<
" Filename: " << request.filename() <<
" Threshold: " << request.threshold() << std::endl;
gazebo::transport::PublisherPtr imagePub =
node->Advertise<collision_map_creator_msgs::msgs::CollisionMapRequest>("~/collision_map/command");
imagePub->WaitForConnection();
imagePub->Publish(request);
gazebo::transport::fini();
return 0;
}
return -1;
}
代码说明
- 首先是包含必需的标准C++头文件:
#include <iostream>
#include <math.h>
#include <boost/shared_ptr.hpp>
#include <sdf/sdf.hh>
#include <boost/gil/gil_all.hpp>
#include <boost/gil/extension/io/png_dynamic_io.hpp>
- 我们的可执行文件也需要gazebo的必要头文件:
#include "gazebo/gazebo.hh"
#include "gazebo/common/common.hh"
#include "gazebo/math/Vector3.hh"
#include "gazebo/transport/transport.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/msgs/msgs.hh"
- 下面这个是与自定义消息类型相关的头文件:
#include "collision_map_request.pb.h"
- 下面这个函数将“(x1,y1)(x2,y2)(x3,y3)(x4,y4)”定义的坐标字符串解析到Vector2d消息的双端队列中。
bool createVectorArray(const char * vectorString,
deque<gazebo::msgs::Vector2d*> corners)
- 下面对双端队列迭代器进行初始化:
deque<gazebo::msgs::Vector2d*>::iterator it;
- 遍历拐点双端队列:
...
for (it = corners.begin(); it != corners.end(); ++it)
{
...
}
- 对于这个拐点Vector2d,通过将找到的每个x和y的字符串转换为浮点数来设置X和Y:
(*it)->set_x(atof(x.c_str()));
(*it)->set_y(atof(y.c_str()));
- 下面是主函数,当可执行文件运行时会调用该主函数:
int main(int argc, char * argv[])
{
...
}
- 该可执行文件需要多个参数,只有在提供至少四个参数的情况下,才能继续进行处理:
if (argc > 4)
{
...
}
- 下面会创建一条CollisionMapRequest消息。需要先填写此消息内容,然后再发送该消息。另外还初始化了一个Vector2d消息的双端队列,这样可以将它们传递给createVectorArray函数:
collision_map_creator_msgs::msgs::CollisionMapRequest request;
deque<gazebo::msgs::Vector2d*> corners;
- 如果消息字段是简单的数据类型(双精度,int32,字符串),则可以通过其关联的set_field()方法直接进行设置。如果该字段本身是一种消息类型,则必须通过其mutable_field()方法对其进行访问。因为Vector2d本身是一条单独的消息,所以必须首先从其mutable函数调用中获取指针,如下所示:
corners.push_back(request.mutable_upperleft());
corners.push_back(request.mutable_upperright());
corners.push_back(request.mutable_lowerright());
corners.push_back(request.mutable_lowerleft());
- 将Vector2d指针的双端队列和第一个argv字符串传递给createVectorArray方法。如果失败,则输入的格式可能不正确。在这种情况下,需要退出程序。
if (!createVectorArray(argv[1],corners))
{
return -1;
}
- 对于简单字段,可以通过调用它们的set_field方法直接设置它们的值:
request.set_height(atof(argv[2]));
request.set_resolution(atof(argv[3]));
request.set_filename(argv[4]);
- 对于可选的阈值字段,如果在命令参数中指定了阈值字段,则需要设置该可选阈值字段。
if (argc == 6)
{
request.set_threshold(atoi(argv[6]));
}
- 下面是主函数中超级重要的一部分,即对gazebo传输系统进行初始化。对于插件,Gazebo已经进行了传输系统的初始化,但是对于用户自定义的可执行文件,则必须自己完成gazebo传输系统的初始化。另外还需要注意,这里没有使用gazebo命名空间,因此必须显式进行初始化:
gazebo::transport::init();
gazebo::transport::run();
gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init("default");
- 下一行代码会在话题~/collision_map/command上初始化请求发布者(Request Publisher):
gazebo::transport::PublisherPtr imagePub =
node->Advertise<collision_map_creator_msgs::msgs::CollisionMapRequest>("~/collision_map/command");
- 要发布自定义消息,必须首先等待发布者连接到主节点上(master)。 然后,就可以直接发布该自定义消息。
imagePub->WaitForConnection();
imagePub->Publish(request);
- 在退出之前,程序必须调用transport :: fini()函数将gazebo传输系统全部关闭。
gazebo::transport::fini();
插件和可执行文件的CMakeLists
- 下面是编译该插件和可执行文件所需的CMakeLists.txt文件内容:
# 2.8.8 required to use PROTOBUF_IMPORT_DIRS
cmake_minimum_required(VERSION 2.8.8 FATAL_ERROR)
FIND_PACKAGE( Boost 1.40 COMPONENTS system REQUIRED )
set (CMAKE_CXX_FLAGS "-g -Wall -std=c++11")
find_package(gazebo REQUIRED)
include_directories(
${GAZEBO_INCLUDE_DIRS}
${SDF_INCLUDE_DIRS}
${CMAKE_CURRENT_BINARY_DIR}/msgs
)
link_directories(${GAZEBO_LIBRARY_DIRS} ${CMAKE_CURRENT_BINARY_DIR}/msgs)
add_subdirectory(msgs)
add_executable (request_publisher http://request_publisher.cc)
target_link_libraries(request_publisher collision_map_creator_msgs ${GAZEBO_LIBRARIES} ${Boost_LIBRARIES} ${SDF_LIBRARIES})
add_dependencies(request_publisher collision_map_creator_msgs)
add_library(collision_map_creator SHARED http://collision_map_creator.cc )
target_link_libraries(collision_map_creator collision_map_creator_msgs ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${SDF_LIBRARIES})
add_dependencies(collision_map_creator collision_map_creator_msgs)
代码说明
- 在插件的回调函数中,Boost是必需的。更不用说,Boost还要用于图像写入程序。
FIND_PACKAGE( Boost 1.40 COMPONENTS system REQUIRED )
- 需要将msgs目录添加到包含目录,因为在可执行文件和插件中都要使用该目录中的消息。
include_directories(
${GAZEBO_INCLUDE_DIRS}
${CMAKE_CURRENT_BINARY_DIR}/msgs
)
- 除了标准的GAZEBO_LIBRARY_DIRS,还需要链接到msgs目录。指令add_subdirectory告知CMake在其中查找CMakeLists.txt文件。
link_directories(${GAZEBO_LIBRARY_DIRS} ${SDF_LIBRARY_DIRS} ${CMAKE_CURRENT_BINARY_DIR}/msgs)
add_subdirectory(msgs)
- 将可执行文件request_publisher添加到makefile中。必须将该可执行文件链接到collision_map_creator_msgs,GAZEBO_LIBRARIES和Boost_LIBRARIES。指令add_dependencies告知CMake首先构建collision_map_creator_msgs。
add_executable (request_publisher http://request_publisher.cc)
target_link_libraries(request_publisher collision_map_creator_msgs ${GAZEBO_LIBRARIES} ${Boost_LIBRARIES} ${SDF_LIBRARIES})
add_dependencies(request_publisher collision_map_creator_msgs)
- 下面将会构建插件,而且与标准的WorldPlugin CMakeLists.txt非常相似,不同之处在于必须将其链接到collision_map_creator_msgs并将其也添加为依赖项。
add_library(collision_map_creator SHARED http://collision_map_creator.cc )
target_link_libraries(collision_map_creator collision_map_creator_msgs ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${SDF_LIBRARIES})
add_dependencies(collision_map_creator collision_map_creator_msgs)
构建和部署
- 首先需要安装依赖包protobuf-compiler,命令为:
sudo apt-get install protobuf-compiler
- 要构建编译本项目,需要创建一个build目录并进入该目录、运行CMake然后再运行make:
cd ~/collision_map_creator_plugin
mkdir build
cd build
cmake ../
make
- 需要将该插件添加到Gazebo的插件路径中。可以更改环境变量以引用这个build目录,命令为:
export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:collision_map_creator_plugin/build
- 或者也可以将该插件复制到您的插件目录中,命令如下:
sudo cp libcollision_map_creator.so /usr/lib/gazebo-11/plugins/
运行示例
- 假设一切正常,而这可能是一个很粗略的假设(严格来说,这个假设很长),需要用下面这个自定义的仿真世界文件来运行Gazebo:
<?xml version ='1.0'?>
<sdf version ='1.4'>
<world name='default'>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://willowgarage</uri>
</include>
<plugin filename="libcollision_map_creator.so" name="collision_map_creator"/>
</world>
</sdf>
- 用这个仿真世界运行Gazebo,命令为:
gazebo ~/collision_map_creator_plugin/map_creator.world
- 在另一个单独的终端中,运行该可执行文件并指示它构建一幅分辨率为1cm、大小为20m×20m的地图,命令为:
~/collision_map_creator_plugin/build/request_publisher "(-10,10)(10,10)(10,-10)(-10,-10)" 10 0.01 ~/map.png
- 该可执行文件终端应该会显示它与Gazebo的连接并显示请求消息。在Gazebo终端中应该可以看到显示一些消息并运行地图绘制完成百分比统计数值直到完成该地图绘制为止。您的map.png应该看起来像下面这幅图。
参考:
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号