Beginner Guide 2 - Create a package
This guide is a short version of ROS Tutorial for Beginner which shows the methods to create a new package in ROS, both in C++ and Python.
Last update: 2022-05-07
Table of Content
This guide was created by using ROS Melodic on Ubuntu 18.04 LTS.
The official guide is at https://wiki.ros.org/ROS/Tutorials.
An ebook for further reference: A Gentle Introduction to ROS by Jason M. O’Kane.
Create ROS msg
and srv
#
The msg files are simple text files that describe the fields of a ROS message. They are used to generating source code for messages in different languages. The msg files are stored in the msg
directory of a package
The field types include:
int8
,int16
,int32
,int64
float32
,float64
string
time
,duration
- other
msg
files - variable-length
array[]
and fixed-lengtharray[x]
There is also a special type in ROS: Header
, the header contains a timestamp and coordinate frame information that are commonly used in ROS.
Here is an example of a msg that uses a Header
, a string
primitive, and two other messages :
Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist
The srv file describes a service. It is composed of two parts: a request and a response, and srv files are stored in the srv
directory. The two parts are separated by a ‘—‘ line.
Here is an example of a srv file:
int64 A
int64 B
---
int64 Sum
In the above example, A and B are the request, and Sum is the response.
Create a msg
#
Let’s define a new msg in the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir msg && \
echo "int64 num" > msg/Num.msg
Using rosmsg
to see a message definition:
rosmsg show beginner_tutorials/Num
Creating a srv
#
Let’s define a new msg in the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir srv && \
touch srv/AddTwoInts.srv
The file content:
int64 a
int64 b
---
int64 sum
Using rossrv
to see a service definition:
rossrv show beginner_tutorials/AddTwoInts
Generate msg
and srv
#
To make sure that the msg files are turned into source code for C++, Python, and other languages, open package.xml
, and make sure these two lines are in it:
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
and then add these packages into the CMakeLists.txt
file:
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## 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 added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)
make the package again:
roscd beginner_tutorials && \
cd ../.. && \
catkin_make && \
cd -
Any .msg
file in the msg directory will generate code for use in all supported languages:
- The C++ message header file will be generated in
catkin_ws/devel/include/beginner_tutorials/
. - The Python script will be created in
catkin_ws/devel/lib/python2.7/dist-packages/beginner_tutorials/msg
. - The lisp file appears in
catkin_ws/devel/share/common-lisp/ros/beginner_tutorials/msg/
.
Similarly, any .srv
files in the srv directory will have generated code in supported languages.
- For C++, this will generate header files in the same directory as the messages.
- For Python and Lisp, there will be a
srv
folder beside themsg
folders.
Here are the generated files:
Let’s see what was generated!
In the Num.h header file:
-
Create a namespace based on the package name
namespace beginner_tutorials {}
-
Use a template of an Allocator to create a new Num type:
template <class ContainerAllocator> struct Num_ { typedef Num_<ContainerAllocator> Type; // constructor Num_() : num(0) { } Num_(const ContainerAllocator& _alloc) : num(0) { (void)_alloc; } // members typedef int64_t _num_type; _num_type num; // define new type of pointer typedef boost::shared_ptr< ::beginner_tutorials::Num_<ContainerAllocator> > Ptr; typedef boost::shared_ptr< ::beginner_tutorials::Num_<ContainerAllocator> const> ConstPtr; }; // struct Num_
-
Create new pointer types of this new Num type
typedef ::beginner_tutorials::Num_< std::allocator<void> > Num; typedef boost::shared_ptr< ::beginner_tutorials::Num > NumPtr; typedef boost::shared_ptr< ::beginner_tutorials::Num const> NumConstPtr;
Noted that ROS uses
shared_ptr
to manage the memory, that will prevent any memory leak issue. -
Create friendly operations
template<class ContainerAllocator> struct Printer< ::beginner_tutorials::Num_<ContainerAllocator> > { template<typename Stream> static void stream( Stream& s, const std::string& indent, const ::beginner_tutorials::Num_<ContainerAllocator>& v) { s << indent << "num: "; Printer<int64_t>::stream(s, indent + " ", v.num); } }; template<typename ContainerAllocator> std::ostream& operator<<( std::ostream& s, const ::beginner_tutorials::Num_<ContainerAllocator> & v) { ros::message_operations::Printer< ::beginner_tutorials::Num_<ContainerAllocator> > ::stream(s, "", v); return s; } template<typename ContainerAllocator1, typename ContainerAllocator2> bool operator==( const ::beginner_tutorials::Num_<ContainerAllocator1> & lhs, const ::beginner_tutorials::Num_<ContainerAllocator2> & rhs) { return lhs.num == rhs.num; } template<typename ContainerAllocator1, typename ContainerAllocator2> bool operator!=( const ::beginner_tutorials::Num_<ContainerAllocator1> & lhs, const ::beginner_tutorials::Num_<ContainerAllocator2> & rhs) { return !(lhs == rhs); }
-
Metadata which will be used by ROS to show object’s information
template <class ContainerAllocator> struct IsFixedSize< ::beginner_tutorials::Num_<ContainerAllocator> > : TrueType { }; template <class ContainerAllocator> struct IsFixedSize< ::beginner_tutorials::Num_<ContainerAllocator> const> : TrueType { }; template <class ContainerAllocator> struct IsMessage< ::beginner_tutorials::Num_<ContainerAllocator> > : TrueType { }; template <class ContainerAllocator> struct IsMessage< ::beginner_tutorials::Num_<ContainerAllocator> const> : TrueType { }; template <class ContainerAllocator> struct HasHeader< ::beginner_tutorials::Num_<ContainerAllocator> > : FalseType { }; template <class ContainerAllocator> struct HasHeader< ::beginner_tutorials::Num_<ContainerAllocator> const> : FalseType { }; template<class ContainerAllocator> struct MD5Sum< ::beginner_tutorials::Num_<ContainerAllocator> > { static const char* value() { return "57d3c40ec3ac3754af76a83e6e73127a"; } static const char* value( const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); } static const uint64_t static_value1 = 0x57d3c40ec3ac3754ULL; static const uint64_t static_value2 = 0xaf76a83e6e73127aULL; }; template<class ContainerAllocator> struct DataType< ::beginner_tutorials::Num_<ContainerAllocator> > { static const char* value() { return "beginner_tutorials/Num"; } static const char* value( const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); } }; template<class ContainerAllocator> struct Definition< ::beginner_tutorials::Num_<ContainerAllocator> > { static const char* value() { return "int64 num\n"; } static const char* value( const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); } };
Publisher and Subscriber (C++)#
Go to the source code folder of the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir src && \
cd src
A Publisher Node#
This tutorial demonstrates simple sending of messages over the ROS system.
nano talker.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
int main(int argc, char **argv)
{
// init with a name
ros::init(argc, argv, "talker");
// create a node
ros::NodeHandle n;
// publish on a the `chatter` topic, queue = 1000
ros::Publisher chatter_pub = n.advertise<std_msgs::String>(
"chatter",
1000
);
// publishing rate 1 Hz
ros::Rate loop_rate(1);
// main loop
int count = 0;
while (ros::ok()) {
// message
std_msgs::String msg;
// content
std::stringstream ss;
ss << "hello world " << count++;
msg.data = ss.str();
ROS_INFO("%s", msg.data.c_str());
// publish
chatter_pub.publish(msg);
// check status
ros::spinOnce();
// sleep
loop_rate.sleep();
}
return 0;
}
A Subscriber Node#
This tutorial demonstrates simple receipt of messages over the ROS system.
nano listener.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
ROS_INFO("I heard: [%s]", msg->data.c_str());
}
int main(int argc, char **argv)
{
// init with a name
ros::init(argc, argv, "listener");
// create a node
ros::NodeHandle n;
// subscribe on a the `chatter` topic, queue = 1000
// execute chatterCallback on receive
ros::Subscriber sub = n.subscribe(
"chatter",
1000,
chatterCallback
);
// main loop
ros::spin();
return 0;
}
Building new nodes#
Add the source code files which need to be compiled into the CMakeLists.txt
. With all dependency packages listed above, add below lines also:
cd .. && \
nano CMakeLists.txt
## Declare a C++ executable
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)
This will create two executables, talker and listener, which by default will go into package directory in devel space, located by default at catkin_ws/devel/lib/<package name>
.
Finally, make the package again:
roscd beginner_tutorials && \
cd ../.. && \
catkin_make && \
cd -
Run new nodes#
Run roscore
first if it is not running. Then run 2 new nodes in two terminals:
rosrun beginner_tutorials talker
rosrun beginner_tutorials listener
Publisher and Subscriber (Python)#
Go to the scripts’ folder of the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir scripts && \
cd scripts
A Publisher Node#
This tutorial demonstrates simple sending of messages over the ROS system.
Note that a node is created from a publisher, in contrast to C++ implementation, a publisher is created from a node.
In ROS, nodes are uniquely named. If two nodes with the same name are launched, the previous one is kicked off. The anonymous=True
flag means that rospy will choose a unique name for a new listener
node so that multiple listeners can run simultaneously.
nano talker.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def talker():
# create a publisher, on topic `chatter`
pub = rospy.Publisher('chatter', String, queue_size=10)
# create a node
rospy.init_node('talker', anonymous=True)
# set the rate of publishing
rate = rospy.Rate(1) # 1hz
# main loop
while not rospy.is_shutdown():
# make content
hello_str = "hello world %s" % rospy.get_time()
rospy.loginfo(hello_str)
# publish a message
pub.publish(hello_str)
rate.sleep()
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass
A Subscriber Node#
This tutorial demonstrates simple receipt of messages over the ROS system.
nano listener.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def callback(data):
rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
def listener():
# create a node
rospy.init_node('listener', anonymous=True)
# create a subcriber
rospy.Subscriber("chatter", String, callback)
# spin() simply keeps python from exiting until this node is stopped
rospy.spin()
if __name__ == '__main__':
listener()
The function rospy.spin()
simply keeps the node from exiting until the node has been shutdown. Unlike roscpp, rospy.spin()
does not affect the subscriber callback functions, as those have their own threads.
Make script executable#
Scripts need to get execution permission before they can run:
chmod +x *
Building new nodes#
Add the source code files which need to be compiled into the CMakeLists.txt
. With all dependency packages listed above, add below lines also:
cd .. && \
nano CMakeLists.txt
catkin_install_python(PROGRAMS
scripts/talker.py
scripts/listener.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
Finally, make the package again:
roscd beginner_tutorials && \
cd ../.. && \
catkin_make && \
cd -
Run new nodes#
Run roscore
first if it is not running. Then run 2 new nodes in two terminals:
rosrun beginner_tutorials talker.py
rosrun beginner_tutorials listener.py
Python script execution
If the error /usr/bin/env: ‘python\r’: No such file or directory
shows up, it is because of the ending line characters. Unix use LF
only while Windows use CRLF
. Save python scripts in Unix ending character only.
Service and Client (C++)#
Go to the source code folder of the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir src && \
cd src
A Service Node#
This guide will create the service add_two_ints_server
node which will receive two numbers and return the sum.
This service uses the beginner_tutorials/AddTwoInts.h
header file generated from the srv file that is created earlier.
nano add_two_ints_server.cpp
#include "ros/ros.h"
#include "beginner_tutorials/AddTwoInts.h"
// service fuction
bool add(beginner_tutorials::AddTwoInts::Request &req,
beginner_tutorials::AddTwoInts::Response &res)
{
res.sum = req.a + req.b;
ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
ROS_INFO("sending back response: [%ld]", (long int)res.sum);
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "add_two_ints_server");
// create a node
ros::NodeHandle n;
// node will have a service
ros::ServiceServer service = n.advertiseService("add_two_ints", add);
ROS_INFO("Ready to add two ints.");
// main loop
ros::spin();
return 0;
}
A Client Node#
This guide will create the service add_two_ints_client
node which will receive two ints and return the sum.
nano add_two_ints_client.cpp
#include "ros/ros.h"
#include "beginner_tutorials/AddTwoInts.h"
#include <cstdlib>
int main(int argc, char **argv)
{
// check args
ros::init(argc, argv, "add_two_ints_client");
if (argc != 3)
{
ROS_INFO("usage: add_two_ints_client X Y");
return 1;
}
// create a node
ros::NodeHandle n;
// node will have a client
ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");
// create a service target
beginner_tutorials::AddTwoInts srv;
// add params
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);
// call to service
if (client.call(srv)) {
ROS_INFO("Sum: %ld", (long int)srv.response.sum);
} else {
ROS_ERROR("Failed to call service add_two_ints");
return 1;
}
return 0;
}
Building new nodes#
Add the source code files which need to be compiled into the CMakeLists.txt
. With all dependency packages listed above, add below lines also:
cd .. && \
nano CMakeLists.txt
## Declare a C++ executable
add_executable(add_two_ints_server src/add_two_ints_server.cpp)
target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
add_dependencies(add_two_ints_server beginner_tutorials_gencpp)
add_executable(add_two_ints_client src/add_two_ints_client.cpp)
target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
add_dependencies(add_two_ints_client beginner_tutorials_gencpp)
This will create two executables, add_two_ints_server and add_two_ints_client, which by default will go into package directory in devel space, located by default at catkin_ws/devel/lib/<package name>
.
Finally, make the package again:
roscd beginner_tutorials && \
cd ../.. && \
catkin_make && \
cd -
Run new nodes#
Run roscore
first if it is not running. Then run 2 new nodes in two terminals:
rosrun beginner_tutorials add_two_ints_server
rosrun beginner_tutorials add_two_ints_client 1 2
Service and Client (Python)#
Go to the source code folder of the beginner_tutorials
package:
roscd beginner_tutorials && \
mkdir scripts && \
cd scripts && \
A Service Node#
This guide will create the service add_two_ints_server
node which will receive two ints and return the sum.
This service uses the beginner_tutorials/AddTwoInts.h
header file generated from the srv file that is created earlier.
nano add_two_ints_server.py
#!/usr/bin/env python
from __future__ import print_function
from beginner_tutorials.srv import AddTwoInts,AddTwoIntsResponse
import rospy
def handle_add_two_ints(req):
print("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
return AddTwoIntsResponse(req.a + req.b)
def add_two_ints_server():
rospy.init_node('add_two_ints_server')
s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
print("Ready to add two ints.")
rospy.spin()
if __name__ == "__main__":
add_two_ints_server()
A Client Node#
This guide will create the service add_two_ints_client
node which will receive two ints and return the sum.
nano add_two_ints_client.py
#!/usr/bin/env python
from __future__ import print_function
import sys
import rospy
from beginner_tutorials.srv import *
def add_two_ints_client(x, y):
rospy.wait_for_service('add_two_ints')
try:
add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
resp1 = add_two_ints(x, y)
return resp1.sum
except rospy.ServiceException as e:
print("Service call failed: %s"%e)
def usage():
return "%s [x y]"%sys.argv[0]
if __name__ == "__main__":
if len(sys.argv) == 3:
x = int(sys.argv[1])
y = int(sys.argv[2])
else:
print(usage())
sys.exit(1)
print("Requesting %s+%s"%(x, y))
print("%s + %s = %s"%(x, y, add_two_ints_client(x, y)))
Make scripts executable#
Scripts need to get execution permission before they can run:
chmod +x *
Building new nodes#
Add the source code files which need to be compiled into the CMakeLists.txt
. With all dependency packages listed above, add below lines also:
cd .. && \
nano CMakeLists.txt
catkin_install_python(PROGRAMS
scripts/add_two_ints_server.py
scripts/add_two_ints_client.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
This will create two executables, add_two_ints_server and add_two_ints_client, which by default will go into package directory in devel space, located by default at catkin_ws/devel/lib/<package name>
.
Finally, make the package again:
roscd beginner_tutorials && \
cd ../.. && \
catkin_make && \
cd -
Run new nodes#
Run roscore
first if it is not running. Then run 2 new nodes in two terminals:
rosrun beginner_tutorials add_two_ints_server.py
rosrun beginner_tutorials add_two_ints_client.py 1 3
Reference#
There is an interesting book named A Gentle Introduction to ROS by Jason M. O’Kane published on https://cse.sc.edu/~jokane/agitr/. This book supplements ROS’s own documentation, explaining how to interact with existing ROS systems and how to create new ROS programs using C++, with special attention to common mistakes and misunderstandings.
An excerpt from the book:
Giving ROS control
The final complication is that ROS will only execute our callback function when we give it explicit permission to do so. There are actually two slightly different ways to accomplish this. One version looks like this:
ros::spinOnce();
This code asks ROS to execute all of the pending callbacks from all of the node’s subscriptions, and then return control back to us. The other option looks like this:
ros::spin();
This alternative to ros::spinOnce()
asks ROS to wait for and execute callbacks until the node shuts down. In other words, ros::spin()
is roughly equivalent to this loop:
while(ros::ok()) {
ros::spinOnce();
}
The question of whether to use ros::spinOnce()
or ros::spin()
comes down to this:
Does your program have any repetitive work to do, other than responding to callbacks?
- If the answer is No, then use
ros::spin()
. - If the answer is Yes, then a reasonable option is to write a loop that does that other work and calls
ros::spinOnce()
periodically to process callbacks.
A common error in subscriber programs is to mistakenly omit both ros::spinOnce()
and ros::spin()
. In this case, ROS never has an opportunity to execute your callback function.
- Omitting
ros::spin()
will likely cause your program to exit shortly after it starts. - Omitting
ros::spinOnce()
might make it appear as though no messages are being received.