0%

ros publisher and subscriber tutorial

Guide

create workspace

Let’s create and build a catkin workspace:

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/
catkin_make
source devel/setup.bash 
env | grep ROS

create package

cd ~/catkin_ws/src
catkin_create_pkg beginner_tutorials roscpp rospy std_msgs

tree .
.
├── beginner_tutorials
│   ├── CMakeLists.txt
│   ├── include
│   │   └── beginner_tutorials
│   ├── package.xml
│   └── src
└── CMakeLists.txt -> /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake

4 directories, 3 files

create msg

roscd beginner_tutorials
mkdir msg
echo "int64 num" > msg/Num.msg

vim package.xml

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>

vim CMakeLists.txt

find_package(catkin REQUIRED COMPONENTS
   roscpp
   rospy
   std_msgs
   message_generation
)

catkin_package(
  ...
  CATKIN_DEPENDS message_runtime ...
  ...)


add_message_files(
  FILES
  Num.msg
)

create srv

roscd beginner_tutorials
mkdir srv
roscp rospy_tutorials AddTwoInts.srv srv/AddTwoInts.srv

roscp [package_name] [file_to_copy_path] [copy_path]
roscp rospy_tutorials AddTwoInts.srv srv/AddTwoInts.srv

vim CMakeLists.txt

add_service_files(
  FILES
  AddTwoInts.srv
)

show msg

rosmsg show beginner_tutorials/Num
int64 num

rosmsg show Num
[beginner_tutorials/Num]:
int64 num

show srv

rossrv show

rossrv show beginner_tutorials/AddTwoInts 

int64 a
int64 b
---
int64 sum


rossrv show AddTwoInts

[beginner_tutorials/AddTwoInts]:
int64 a
int64 b
---
int64 sum

[rospy_tutorials/AddTwoInts]:
int64 a
int64 b
---
int64 sum

Code Example

talker.cpp

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
#include "ros/ros.h"
#include "std_msgs/String.h"

#include <sstream>

/**
* This tutorial demonstrates simple sending of messages over the ROS system.
*/
int main(int argc, char **argv)
{
/**
* The ros::init() function needs to see argc and argv so that it can perform
* any ROS arguments and name remapping that were provided at the command line.
* For programmatic remappings you can use a different version of init() which takes
* remappings directly, but for most command-line programs, passing argc and argv is
* the easiest way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "talker");

/**
* NodeHandle is the main access point to communications with the ROS system.
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
ros::NodeHandle n;

/**
* The advertise() function is how you tell ROS that you want to
* publish on a given topic name. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. After this advertise() call is made, the master
* node will notify anyone who is trying to subscribe to this topic name,
* and they will in turn negotiate a peer-to-peer connection with this
* node. advertise() returns a Publisher object which allows you to
* publish messages on that topic through a call to publish(). Once
* all copies of the returned Publisher object are destroyed, the topic
* will be automatically unadvertised.
*
* The second parameter to advertise() is the size of the message queue
* used for publishing messages. If messages are published more quickly
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);

ros::Rate loop_rate(10);

/**
* A count of how many messages we have sent. This is used to create
* a unique string for each message.
*/
int count = 0;
while (ros::ok())
{
/**
* This is a message object. You stuff it with data, and then publish it.
*/
std_msgs::String msg;

std::stringstream ss;
ss << "hello world " << count;
msg.data = ss.str();

ROS_INFO("%s", msg.data.c_str());

/**
* The publish() function is how you send messages. The parameter
* is the message object. The type of this object must agree with the type
* given as a template parameter to the advertise<>() call, as was done
* in the constructor above.
*/
chatter_pub.publish(msg);

ros::spinOnce();

loop_rate.sleep();
++count;
}


return 0;
}

listener.cpp

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
#include "ros/ros.h"
#include "std_msgs/String.h"

/**
* This tutorial demonstrates simple receipt of messages over the ROS system.
*/
void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
ROS_INFO("I heard: [%s]", msg->data.c_str());
}

int main(int argc, char **argv)
{
/**
* The ros::init() function needs to see argc and argv so that it can perform
* any ROS arguments and name remapping that were provided at the command line.
* For programmatic remappings you can use a different version of init() which takes
* remappings directly, but for most command-line programs, passing argc and argv is
* the easiest way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "listener");

/**
* NodeHandle is the main access point to communications with the ROS system.
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
ros::NodeHandle n;

/**
* The subscribe() call is how you tell ROS that you want to receive messages
* on a given topic. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. Messages are passed to a callback function, here
* called chatterCallback. subscribe() returns a Subscriber object that you
* must hold on to until you want to unsubscribe. When all copies of the Subscriber
* object go out of scope, this callback will automatically be unsubscribed from
* this topic.
*
* The second parameter to the subscribe() function is the size of the message
* queue. If messages are arriving faster than they are being processed, this
* is the number of messages that will be buffered up before beginning to throw
* away the oldest ones.
*/
ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

/**
* ros::spin() will enter a loop, pumping callbacks. With this version, all
* callbacks will be called from within this thread (the main one). ros::spin()
* will exit when Ctrl-C is pressed, or the node is shutdown by the master.
*/
ros::spin();

return 0;
}

CMakeLists.txt

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
cmake_minimum_required(VERSION 2.8.3)
project(beginner_tutorials)

## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)

## Generate messages in the 'msg' folder
add_message_files(
FILES
Num.msg
)

## Generate services in the 'srv' folder
add_service_files(
FILES
AddTwoInts.srv
)

## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )

## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)

catkin_package(
INCLUDE_DIRS include
LIBRARIES beginner_tutorials
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(talker src/talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})
add_dependencies(talker beginner_tutorials_generate_messages_cpp)

add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})
add_dependencies(listener beginner_tutorials_generate_messages_cpp)

catkin_make

cd ~/catkin_ws
catkin_make 

Base path: /home/kezunlin/workspace/ros/catkin_ws
Source space: /home/kezunlin/workspace/ros/catkin_ws/src
Build space: /home/kezunlin/workspace/ros/catkin_ws/build
Devel space: /home/kezunlin/workspace/ros/catkin_ws/devel
Install space: /home/kezunlin/workspace/ros/catkin_ws/install
####
#### Running command: "make cmake_check_build_system" in "/home/kezunlin/workspace/ros/catkin_ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/kezunlin/workspace/ros/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /home/kezunlin/workspace/ros/catkin_ws/devel;/home/kezunlin/catkin_ws/devel;/opt/ros/kinetic
-- This workspace overlays: /home/kezunlin/workspace/ros/catkin_ws/devel;/home/kezunlin/catkin_ws/devel;/opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/kezunlin/workspace/ros/catkin_ws/build/test_results
-- Found gtest: gtests will be built
-- Using Python nosetests: /usr/local/bin/nosetests-2.7
-- catkin 0.7.14
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~  traversing 1 packages in topological order:
-- ~~  - beginner_tutorials
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'beginner_tutorials'
-- ==> add_subdirectory(beginner_tutorials)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- beginner_tutorials: 1 messages, 1 services
-- Configuring done
-- Generating done
-- Build files have been written to: /home/kezunlin/workspace/ros/catkin_ws/build
####
#### Running command: "make -j8 -l8" in "/home/kezunlin/workspace/ros/catkin_ws/build"
####
[  0%] [  0%] [  0%] [  0%] Built target std_msgs_generate_messages_cpp
Built target std_msgs_generate_messages_py
[  0%] Built target std_msgs_generate_messages_nodejs
Built target std_msgs_generate_messages_lisp
Built target std_msgs_generate_messages_eus
[  0%] [  0%] Built target _beginner_tutorials_generate_messages_check_deps_AddTwoInts
Built target _beginner_tutorials_generate_messages_check_deps_Num
[ 20%] [ 20%] [ 20%] [ 26%] [ 33%] [ 40%] [ 46%] Generating Lisp code from beginner_tutorials/Num.msg
Generating EusLisp code from beginner_tutorials/AddTwoInts.srv
Generating EusLisp code from beginner_tutorials/Num.msg
Generating Javascript code from beginner_tutorials/Num.msg
Generating Javascript code from beginner_tutorials/AddTwoInts.srv
Generating C++ code from beginner_tutorials/Num.msg
[ 53%] Generating C++ code from beginner_tutorials/AddTwoInts.srv
Generating Python from MSG beginner_tutorials/Num
[ 60%] Generating Lisp code from beginner_tutorials/AddTwoInts.srv
[ 66%] Generating Python code from SRV beginner_tutorials/AddTwoInts
[ 66%] Built target beginner_tutorials_generate_messages_nodejs
[ 73%] Built target beginner_tutorials_generate_messages_eus
[ 73%] Built target beginner_tutorials_generate_messages_lisp
[ 80%] [ 86%] Generating Python srv __init__.py for beginner_tutorials
Generating Python msg __init__.py for beginner_tutorials
[ 86%] Built target beginner_tutorials_generate_messages_cpp
Scanning dependencies of target listener
Scanning dependencies of target talker
[ 93%] [100%] Building CXX object beginner_tutorials/CMakeFiles/listener.dir/src/listener.cpp.o
Building CXX object beginner_tutorials/CMakeFiles/talker.dir/src/talker.cpp.o
[100%] Built target beginner_tutorials_generate_messages_py
[100%] Built target beginner_tutorials_generate_messages
Linking CXX executable /home/kezunlin/workspace/ros/catkin_ws/devel/lib/beginner_tutorials/talker
[100%] Built target talker
Linking CXX executable /home/kezunlin/workspace/ros/catkin_ws/devel/lib/beginner_tutorials/listener
[100%] Built target listener

play with talker and listener

roscore 

cd ~/catkin_ws
./devel/lib/beginner_tutorials/talker
./devel/lib/beginner_tutorials/listener

rosrun beginner_tutorials talker

[ INFO] [1545039519.457624559]: hello world 803
[ INFO] [1545039519.557624500]: hello world 804
[ INFO] [1545039519.657595852]: hello world 805
[ INFO] [1545039519.757538635]: hello world 806

rosrun beginner_tutorials listener

[ INFO] [1545039519.458099942]: I heard: [hello world 803]
[ INFO] [1545039519.558116295]: I heard: [hello world 804]
[ INFO] [1545039519.658085716]: I heard: [hello world 805]
[ INFO] [1545039519.757998160]: I heard: [hello world 806]

Quick Ref

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
# install and configure ros environment
## install
sudo sh -c '. /etc/lsb-release && echo "deb [arch=amd64] http://mirrors.ustc.edu.cn/ros/ubuntu/ $DISTRIB_CODENAME main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116

sudo apt-get update
sudo apt-get install ros-kinetic-desktop-full
sudo apt-get install python-rosinstall python-rosinstall-generator python-wstool build-essential

sudo rosdep init
rosdep update

echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
source ~/.bashrc

env | grep ROS

## test
roscore

## create workspace
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/
catkin_make
source devel/setup.bash
env | grep ROS

commands

  • rospack = ros + pack(age)
  • roscd = ros + cd
  • rosls = ros + ls

sudo apt-get install ros-kinetic-ros-tutorials

rosls roscpp_tutorials

rospack find roscpp

/opt/ros/kinetic/share/roscpp

roscd roscpp
pwd
/opt/ros/kinetic/share/roscpp

Note that roscd, like other ROS tools, will only find ROS packages that are within the directories listed in your ROS_PACKAGE_PATH.
echo $ROS_PACKAGE_PATH

roscd roscpp/cmake
pwd
/opt/ros/kinetic/share/roscpp/cmake

roscd log
pwd
/home/kezunlin/.ros/log/42e6e804-0199-11e9-93c2-80fa5b47928a

rosls roscpp
cmake msg package.xml rosbuild srv

Creating a ROS Package

package structure

workspace_folder/ – WORKSPACE
src/ – SOURCE SPACE
CMakeLists.txt – ‘Toplevel’ CMake file, provided by catkin
package_1/
CMakeLists.txt – CMakeLists.txt file for package_1
package.xml – Package manifest for package_1

package_n/
CMakeLists.txt – CMakeLists.txt file for package_n
package.xml – Package manifest for package_n

create a catkin package

catkin_create_pkg [depend1] [depend2] [depend3]

cd ~/catkin_ws/src
catkin_create_pkg beginner_tutorials roscpp rospy std_msgs

Created file beginner_tutorials/CMakeLists.txt
Created file beginner_tutorials/package.xml
Created folder beginner_tutorials/include/beginner_tutorials
Created folder beginner_tutorials/src

build a catkin workspace and source setup file

cd ~/catkin_ws/
catkin_make

. ~/catkin_ws/devel/setup.bash

package dependencies

first-order dependencies

rospack depends1 beginner_tutorials
roscpp
rospy
std_msgs

roscd beginner_tutorials
cat package.xml

<package format="2">
...
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>
...
</package>

Indirect dependencies

rospack depends1 rospy
genpy
roscpp
rosgraph
rosgraph_msgs
roslib
std_msgs

list all dependencies

rospack depends beginner_tutorials

Customizing Your Package

vim package.xml

Building a ROS Package

catkin_make

# In a CMake project
$ mkdir build
$ cd build
$ cmake ..
$ make
$ make install  # (optionally)

# In a catkin workspace
$ catkin_make
$ catkin_make install  # (optionally)

Understanding ROS Nodes

commands

  • roscore = ros+core : master (provides name service for ROS) + rosout (stdout/stderr) + parameter server (parameter server will be introduced later)
  • rosnode = ros+node : ROS tool to get information about a node.
  • rosrun = ros+run : runs a node from a given package.

concepts

Quick Overview of Graph Concepts

  • Nodes: A node is an executable that uses ROS to communicate with other nodes.
  • Messages: ROS data type used when subscribing or publishing to a topic.
  • Topics: Nodes can publish messages to a topic as well as subscribe to a topic to receive messages.
  • Master: Name service for ROS (i.e. helps nodes find each other)
  • rosout: ROS equivalent of stdout/stderr
  • roscore: Master + rosout + parameter server (parameter server will be introduced later)

Client Libraries

  • rospy = python client library
  • roscpp = c++ client library

play with nodes

roscore

rosnode list
/rosout

rosnode info /rosout

--------------------------------------------------------------------------------
Node [/rosout]
Publications: 
 * /rosout_agg [rosgraph_msgs/Log]

Subscriptions: 
 * /rosout [unknown type]

Services: 
 * /rosout/get_loggers
 * /rosout/set_logger_level


contacting node http://ke:40803/ ...
Pid: 31049

run new nodes

rosrun [package_name] [node_name]

rosrun turtlesim turtlesim_node

rosnode list
/rosout
/turtlesim

rosnode info /turtlesim

rename node name

rosrun turtlesim turtlesim_node __name:=my_turtle

rosnode list
/my_turtle
/rosout

Note: If you still see /turtlesim in the list, it might mean that you stopped the node in the terminal using ctrl-C instead of closing the window

ping node

rosnode ping my_turtle
rosnode: node is [/my_turtle]
pinging /my_turtle with a timeout of 3.0s
xmlrpc reply from http://ke:33523/ time=0.274181ms
xmlrpc reply from http://ke:33523/ time=1.040220ms
xmlrpc reply from http://ke:33523/ time=1.013041ms
^Cping average: 0.775814ms

Understanding ROS Topics

roscore
rosrun turtlesim turtlesim_node
rosrun turtlesim turtle_teleop_key

rosrun rqt_graph rqt_graph

rostopic echo /turtle1/cmd_vel

linear:
x: 2.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0

rostopic list -v

Published topics:
 * /turtle1/color_sensor [turtlesim/Color] 1 publisher
 * /turtle1/cmd_vel [geometry_msgs/Twist] 1 publisher
 * /rosout [rosgraph_msgs/Log] 3 publishers
 * /rosout_agg [rosgraph_msgs/Log] 1 publisher
 * /turtle1/pose [turtlesim/Pose] 1 publisher

Subscribed topics:
 * /turtle1/cmd_vel [geometry_msgs/Twist] 1 subscriber
 * /rosout [rosgraph_msgs/Log] 1 subscriber
 * /statistics [rosgraph_msgs/TopicStatistics] 1 subscriber

rostopic type /turtle1/cmd_vel
geometry_msgs/Twist

rosmsg show geometry_msgs/Twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z

rostopic type /turtle1/cmd_vel | rosmsg show

publish messages

rostopic pub [topic] [msg_type] [args]

rostopic pub /turtle1/cmd_vel geometry_msgs/Twist “linear:
x: 2.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 1.8”

rostopic pub -1 /turtle1/cmd_vel geometry_msgs/Twist – ‘[2.0, 0.0, 0.0]’ ‘[0.0, 0.0, 1.8]’

rostopic pub /turtle1/cmd_vel geometry_msgs/Twist -r 1 – ‘[2.0, 0.0, 0.0]’ ‘[0.0, 0.0, -1.8]’

YAML syntax

rostopic hz /turtle1/pose
$ 60 HZ

rosrun rqt_plot rqt_plot

Understanding ROS Services and Parameters

rosservice

Services are another way that nodes can communicate with each other. Services allow nodes to send a request and receive a response.

rosnode list
/rosout
/rqt_gui_py_node_1614
/teleop_turtle
/turtlesim

rosservice list
/clear
/kill
/reset
/rosout/get_loggers
/rosout/set_logger_level
/rqt_gui_py_node_1614/get_loggers
/rqt_gui_py_node_1614/set_logger_level
/spawn
/teleop_turtle/get_loggers
/teleop_turtle/set_logger_level
/turtle1/set_pen
/turtle1/teleport_absolute
/turtle1/teleport_relative
/turtlesim/get_loggers
/turtlesim/set_logger_level

rosservice type [service]
rosservice call [service] [args]

rosservice type /clear
std_srvs/Empty

rosservice call /clear

clear the background of turtlesim_node

rosservice type /spawn | rossrv show
float32 x
float32 y
float32 theta
string name

string name

rosservice call /spawn 2 2 0.2 “”

This service lets us spawn a new turtle at a given location and orientation. The name field is optional.

rosparam

rosparam list
/background_b
/background_g
/background_r
/rosdistro
/roslaunch/uris/host_ke__35701
/rosversion
/run_id

rosparam set [param_name]
rosparam get [param_name]

rosparam set /background_r 150
rosservice call /clear

rosparam get /
background_b: 255
background_g: 86
background_r: 150
rosdistro: ‘kinetic


roslaunch:
uris: {host_ke__35701: ‘http://ke:35701/'}
rosversion: ‘1.12.14


run_id: eb9e9f1e-01a3-11e9-93c2-80fa5b47928a

rosparam get /background_b
255

rosparam dump [file_name] [namespace]
rosparam load [file_name] [namespace]

rosparam dump params.yaml

rosparam load params.yaml copy
rosparam get /copy/background_b

Using rqt_console and roslaunch

rosrun rqt_console rqt_console
rosrun rqt_logger_level rqt_logger_level

2 windows pop up.

logger levels

Fatal
Error
Warn
Info
Debug

roslaunch starts nodes as defined in a launch file.
roslaunch [package] [filename.launch]

cd ~/catkin_ws
source devel/setup.bash
roscd beginner_tutorials

mkdir launch
cd launch

vim turtle.launch

rosnode list
/mimic
/rosout
/turtlesim1/sim
/turtlesim2/sim

rostopic list
/rosout
/rosout_agg
/turtlesim1/turtle1/cmd_vel
/turtlesim1/turtle1/color_sensor
/turtlesim1/turtle1/pose
/turtlesim2/turtle1/cmd_vel
/turtlesim2/turtle1/color_sensor
/turtlesim2/turtle1/pose

rostopic pub /turtlesim1/turtle1/cmd_vel geometry_msgs/Twist -r 1 – ‘[2.0, 0.0, 0.0]’ ‘[0.0, 0.0, -1.8]’

You will see the two turtlesims start moving even though the publish command is only being sent to turtlesim1.

rosed

rosed roscpp

rosed roscpp Logger.msg

Creating a ROS msg and srv

  • msg: msg files are simple text files that describe the fields of a ROS message. They are used to generate source code for messages in different languages.
  • srv: an srv file describes a service. It is composed of two parts: a request and a response.

msg

msgs are just simple text files with a field type and field name per line. The field types you can use are:

int8, int16, int32, int64 (plus uint*)
float32, float64
string
time, duration
other msg files
variable-length array[] and fixed-length array[C]

There is also a special type in ROS: Header, the header contains a timestamp and coordinate frame information that are commonly used in ROS.

Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist

srv

int64 A
int64 B

int64 Sum

A and B are the request, and Sum is the response.

create msg

roscd beginner_tutorials
mkdir msg
echo “int64 num” > msg/Num.msg

vim package.xml

message_generation
message_runtime

vim CMakeLists.txt

find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)

catkin_package(

CATKIN_DEPENDS message_runtime …
…)

add_message_files(
FILES
Num.msg
)

create srv

roscd beginner_tutorials
mkdir srv

roscp [package_name] [file_to_copy_path] [copy_path]
roscp rospy_tutorials AddTwoInts.srv srv/AddTwoInts.srv

vim CMakeLists.txt

add_service_files(
FILES
AddTwoInts.srv
)

show msg

rosmsg show beginner_tutorials/Num
int64 num

rosmsg show Num
[beginner_tutorials/Num]:
int64 num

show srv

rossrv show
rossrv show beginner_tutorials/AddTwoInts

int64 a
int64 b
---
int64 sum

rossrv show AddTwoInts

[beginner_tutorials/AddTwoInts]:
int64 a
int64 b
---
int64 sum

[rospy_tutorials/AddTwoInts]:
int64 a
int64 b
---
int64 sum

catkin_make

roscd beginner_tutorials
cd ../..
catkin_make install

review

rospack = ros+pack(age) : provides information related to ROS packages
roscd = ros+cd : changes directory to a ROS package or stack
rosls = ros+ls : lists files in a ROS package
roscp = ros+cp : copies files from/to a ROS package
rosmsg = ros+msg : provides information related to ROS message definitions
rossrv = ros+srv : provides information related to ROS service definitions
catkin_make : makes (compiles) a ROS package
rosmake = ros+make : makes (compiles) a ROS package (if you’re not using a catkin workspace)

Writing a Simple Publisher and Subscriber

src

roscd beginner_tutorials
vim src/talker.cpp
vim src/listener.cpp

build

cd ~/catkin_ws
catkin_make

play with talker and listener

roscore

rosrun beginner_tutorials talker

[ INFO] [1545039519.457624559]: hello world 803
[ INFO] [1545039519.557624500]: hello world 804
[ INFO] [1545039519.657595852]: hello world 805
[ INFO] [1545039519.757538635]: hello world 806

rosrun beginner_tutorials listener

[ INFO] [1545039519.458099942]: I heard: [hello world 803]
[ INFO] [1545039519.558116295]: I heard: [hello world 804]
[ INFO] [1545039519.658085716]: I heard: [hello world 805]
[ INFO] [1545039519.757998160]: I heard: [hello world 806]

Reference

History

  • 20181214: created.