示例如何将ros的节点以plugin的形式加入到gazebo中,使它们配合构成虚拟场景。
假如我们构造了传感器,名叫 Velodyne 的传感器功能齐全,但我们没有任何挂钩到机器人中间件,如果想让 ROS和 Gazebo结合,就必须有中间物,这里名叫plugin的中间体。 与 ROS 结合使用的好处之一是可以轻松地在真实世界和模拟世界之间切换。为了实现这一点,我们需要让我们的传感器与 ROS 生态系统很好地配合。
我们将修改我们当前的插件以包含 ROS 传输机制,其方式类似于我们在上一个教程中添加 Gazebo 传输机制的方式。
我们假设您的系统上当前安装了 ROS。
加入头文件到 velodyne_plugin.ccp文件.
- #include
- #include "ros/ros.h"
- #include "ros/callback_queue.h"
- #include "ros/subscribe_options.h"
- #include "std_msgs/Float32.h"
追加一些成员变量到插件( plugin).
- /// \brief A node use for ROS transport
- private: std::unique_ptr
rosNode; -
- /// \brief A ROS subscriber
- private: ros::Subscriber rosSub;
-
- /// \brief A ROS callbackqueue that helps process messages
- private: ros::CallbackQueue rosQueue;
-
- /// \brief A thread the keeps running the rosQueue
- private: std::thread rosQueueThread;
在 Load 函数的末尾,添加以下内容。
- // Initialize ros, if it has not already bee initialized.
- if (!ros::isInitialized())
- {
- int argc = 0;
- char **argv = NULL;
- ros::init(argc, argv, "gazebo_client",
- ros::init_options::NoSigintHandler);
- }
-
- // Create our ROS node. This acts in a similar manner to
- // the Gazebo node
- this->rosNode.reset(new ros::NodeHandle("gazebo_client"));
-
- // Create a named topic, and subscribe to it.
- ros::SubscribeOptions so =
- ros::SubscribeOptions::create
( - "/" + this->model->GetName() + "/vel_cmd",
- 1,
- boost::bind(&VelodynePlugin::OnRosMsg, this, _1),
- ros::VoidPtr(), &this->rosQueue);
- this->rosSub = this->rosNode->subscribe(so);
-
- // Spin up the queue helper thread.
- this->rosQueueThread =
- std::thread(std::bind(&VelodynePlugin::QueueThread, this));
如果您通读代码,您会注意到我们需要两个新函数:OnRosMsg 和 QueueThread。让我们现在添加这些。
- /// \brief Handle an incoming message from ROS
- /// \param[in] _msg A float value that is used to set the velocity
- /// of the Velodyne.
- public: void OnRosMsg(const std_msgs::Float32ConstPtr &_msg)
- {
- this->SetVelocity(_msg->data);
- }
-
- /// \brief ROS helper function that processes messages
- private: void QueueThread()
- {
- static const double timeout = 0.01;
- while (this->rosNode->ok())
- {
- this->rosQueue.callAvailable(ros::WallDuration(timeout));
- }
- }
最后要处理的项目是 cmake 构建.
CMakeLists.txt.修改文件的顶部,如下所示。
- cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
-
- find_package(roscpp REQUIRED)
- find_package(std_msgs REQUIRED)
- include_directories(${roscpp_INCLUDE_DIRS})
- include_directories(${std_msgs_INCLUDE_DIRS})
修改插件的目标链接库。
target_link_libraries(velodyne_plugin ${GAZEBO_LIBRARIES} ${roscpp_LIBRARIES}) 您的 CMakeLists.txt 现在应该如下所示。
- cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
-
- find_package(roscpp REQUIRED)
- find_package(std_msgs REQUIRED)
- include_directories(${roscpp_INCLUDE_DIRS})
- include_directories(${std_msgs_INCLUDE_DIRS})
-
- # Find Gazebo
- find_package(gazebo REQUIRED)
- include_directories(${GAZEBO_INCLUDE_DIRS})
- link_directories(${GAZEBO_LIBRARY_DIRS})
- set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
-
- # Build our plugin
- add_library(velodyne_plugin SHARED velodyne_plugin.cc)
- target_link_libraries(velodyne_plugin ${GAZEBO_LIBRARIES} ${roscpp_LIBRARIES})
-
- # Build the stand-alone test program
- add_executable(vel vel.cc)
-
- if (${gazebo_VERSION_MAJOR} LESS 6)
- include(FindBoost)
- find_package(Boost ${MIN_BOOST_VERSION} REQUIRED system filesystem regex)
- target_link_libraries(vel ${GAZEBO_LIBRARIES} ${Boost_LIBRARIES})
- else()
- target_link_libraries(vel ${GAZEBO_LIBRARIES})
- endif()
确保你已经source了 ROS
source /opt/ros//setup.bash 编译插件.
- cd ~/velodyne_plugin/build
- cmake ../
- make
我们现在可以像往常一样加载 Gazebo 插件,它会在 ROS 主题上监听传入的浮动消息。然后这些消息将用于设置 Velodyne 的转速。
开启 roscore
- source /opt/ros/
/setup.bash - roscore
在新终端中, 启动Gazebo
- cd ~/velodyne_plugin/build
- source /opt/ros/
/setup.bash - gazebo ../velodyne.world
开启新终端l, use rostopic发送速度消息.
- source /opt/ros/
/setup.bash - rostopic pub /my_velodyne/vel_cmd std_msgs/Float32 1.0
更改上述命令的最后一个数字以设置不同的速度。
恭喜,您现在拥有构建自定义模型、共享模型和生成公共 API 的工具。玩得开心,快乐模拟!