美文网首页
编写 launch 文件

编写 launch 文件

作者: OurNote | 来源:发表于2019-03-28 18:01 被阅读0次

引言

之前的文章 介绍了 launch 文件的基本结构和使用方法。

在这里我们用小海龟 (turtlesim)做一下实例练习。

  • 创建一个控制节点 pubvel,向小海龟发布命令,控制它移动;
  • 再创建一个消息显示节点 subpose,实时地将小海龟的位置和角度显示在屏幕上。
  • 创建一个 launch 文件,启动上述节点,并设置相关参数

本文内容主要来自 《A Gentle Introduction to ROS》.

编写 pubvel 节点和 subpose 节点

在该实例中,ros package 名字为 agitr,里面包含了 CMakeLists.txtpackage.xml 文件,以及 src 文件夹,存放源程序。

这里我们用 C++ 编写这两个节点,源程序分别命名为 pubvel.cppsubpose.cpp

pubvel 的作用是发送随机的线速度和角速度指令到小海龟,驱动它随机移动。具体程序如下:

#include <ros/ros.h>
#include <geometry_msgs/Twist.h> // For geometry_msgs:: Twist
#include <stdlib.h> // For rand() and RAND_MAX
int main(int argc,char**argv){
   // Initialize the ROS system and become a node .
   ros::init(argc,argv,"publish_velocity");
   ros::NodeHandle nh;

   // Create a publisher obj ect .
   ros::Publisher pub=nh.advertise<geometry_msgs::Twist>("turtle1/cmd_vel",1000);

   // Seed the random number generator .
   srand(time(0));

   // Loop at 2Hz until the node is shut down.
   ros::Rate rate(2);
   while(ros::ok()){
   // Create and fill in the message . The other four fields , which are ignored by turtlesim , default to 0.
   geometry_msgs::Twist msg;
   msg.linear.x = double(rand())/double(RAND_MAX);
   msg.angular.z = 2*double(rand())/double(RAND_MAX) - 1;
   // Publish the message .
   pub.publish(msg);
   // Send a message to rosout with the details .
   ROS_INFO_STREAM("Sending random velocity command:"<<"linear="<<msg.linear.x<<"angular="<<msg.angular.z);

   // Wait until it's time for another iteration .
   rate.sleep();
   }
}

subpose 节点的功能是实时读取 /turtle1/pose 中小海龟的位置和角度信息,并通过ROS_INFO_STREAM 在终端显示出来。具体程序如下:

#include <ros/ros.h>
#include <turtlesim/Pose.h>
#include <iomanip> // for std::setprecision and std::fixed

// A callback function . Executed each time a new pose message arrives .
void poseMessageReceived(const turtlesim::Pose&msg){
  ROS_INFO_STREAM(std::setprecision(2)<<std::fixed<<"position=("<<msg.x<<","<<msg.y<<")"<<"*direction="<<msg.theta);
}

int main(int argc,char**argv){
  // Initialize the ROS system and become a node .
  ros::init(argc,argv,"subscribe_to_pose");
  ros::NodeHandle nh;

  // Create a subscri ber obj ect .
  ros::Subscriber nsub=nh.subscribe("turtle1/pose",1000,&poseMessageReceived);
  // Let ROS take over .
  ros::spin();
}

编写好了 C++ 源文件,接下来需要为编译做些准备工作。

CmakeLists.txt 文件中相应位置做如下修改,即指定生成两个可执行文件:

find_package(catkin REQUIRED COMPONENTS roscpp geometry_msgs)
add_executable( pubvel src/pubvel.cpp )
add_executable( subpose src/subpose.cpp )
target_link_libraries( pubvel ${catkin_LIBRARIES} )
target_link_libraries( subpose ${catkin_LIBRARIES} )

package.xml 的相应位置做如下修改,即设置编译和运行中的 package 依赖:

<build_depend>roscpp</build_depend>
<build_depend>geometry_msgs</build_depend>
<exec_depend>roscpp</exec_depend> 
<exec_depend>geometry_msgs</exec_depend>

之后用 catkin_make 命令编译。

创建 launch 文件

为了同时启动多个 ros 节点,我们可以创建一个 launch 文件。

agitr package 文件夹内创建一个名为 launch 的文件夹,在其中创建名为 example.launch 的 launch 文件,程序如下:

<launch>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim" respawn="true"/>
<node pkg="turtlesim" type="turtle_teleop_key" name="teleop_key" required="true" launch-prefix="xterm -e"/>
<node pkg="agitr" type="pubvel" name="pubvel" launch-prefix="xterm -e"/>
<node pkg="agitr" type="subpose" name="subpose" launch-prefix="xterm -e" output="screen"/>
</launch>

上边命令的具体含义可以参考之前的文章

该 launch 文件的目的是启动 turtlesim 仿真平台节点,键盘控制节点,以及我们上边编写的 pubvel 节点和 subpose 节点。

在终端启动 launch 文件的命令如下:

roslaunch agitr example.launch

如果一切顺利,应该可以看到 turtlesim 窗口,同时终端会显示出小海龟的姿态信息,类似下图所示:

2019-03-28 17-53-50屏幕截图.png

Written by SH
Revised by QP

相关文章

网友评论

      本文标题:编写 launch 文件

      本文链接:https://www.haomeiwen.com/subject/cyrcbqtx.html