• 欢迎访问开心洋葱网站,在线教程,推荐使用最新版火狐浏览器和Chrome浏览器访问本网站,欢迎加入开心洋葱 QQ群
  • 为方便开心洋葱网用户,开心洋葱官网已经开启复制功能!
  • 欢迎访问开心洋葱网站,手机也能访问哦~欢迎加入开心洋葱多维思维学习平台 QQ群
  • 如果您觉得本站非常有看点,那么赶紧使用Ctrl+D 收藏开心洋葱吧~~~~~~~~~~~~~!
  • 由于近期流量激增,小站的ECS没能经的起亲们的访问,本站依然没有盈利,如果各位看如果觉着文字不错,还请看官给小站打个赏~~~~~~~~~~~~~!

gazebo教程(七) 连接ros

人工智能 我是。 1865次浏览 0个评论

连接ros

  • 添加ROS插件
  • 在ROS中控制Velodyne

  在之前的文章中,我们构建的Velodyne传感器已经具有完整的功能,但这仅局限与仿真而已,与真实的机器人系统很难产生实际联系。因此,我们需要将gazebo与ros连接在一起,这样做的好处之一是,可以轻松地在真实世界和模拟世界之间进行切换,也就是说,你在仿真环境中实现的功能,在某些现实情况下,也能够轻易实现。为了做到这一点,我们需要让我们的传感器与ROS生态系统完美配合。  

添加ROS插件

  修改我们当前的插件内容,在其中添加ROS插件,其方式类似于在上一教程中添加Gazebo插件的方式。假设您的系统上当前已安装ROS。   1、在velodyne_plugin.cc文件中添加头文件。  

#include <thread>
#include "ros/ros.h"
#include "ros/callback_queue.h"
#include "ros/subscribe_options.h"
#include "std_msgs/Float32.h"

  2、向插件添加一些成员变量。  

/// \brief A node use for ROS transport
private: std::unique_ptr<ros::NodeHandle> 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;

  3、在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<std_msgs::Float32>(
      "/" + 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));

  在以上代码中,定义了两个新函数:OnRosMsgQueueThread,具体实现如下,将其添加到相应位置:  

/// \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));
  }
}

  4、最后需要修改的是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()

  5、确保您已获取ROS源:   source /opt/ros/<DISTRO>/setup.bash   6、重新编译插件。  

cd ~/velodyne_plugin/build
cmake ../
make

 

在ROS中控制Velodyne

  现在,我们可以照常加载Gazebo插件,它将在ROS主题上监听传入的浮动数据类型的消息(float)。然后,这些消息将用于设置Velodyne的转速。   1、启动roscore  

source /opt/ros/<DISTRO>/setup.bash
roscore

  2、在新的终端中,启动gazebo  

cd ~/velodyne_plugin/build
source /opt/ros/<DISTRO>/setup.bash
gazebo ../velodyne.world

  3、在新的终端中,使用rostopic发送速度信息。  

source /opt/ros/<DISTRO>/setup.bash
rostopic pub /my_velodyne/vel_cmd std_msgs/Float32 1.0

  更改以上命令的最后一个数字即可以设置不同的速度。  


开心洋葱 , 版权所有丨如未注明 , 均为原创丨未经授权请勿修改 , 转载请注明gazebo教程(七) 连接ros
喜欢 (0)

您必须 登录 才能发表评论!

加载中……