ROS is a heterogeneous multi-processing computing framework for E-Motion robots. This article provides a quick start guide to help one get it running on an Ubuntu 14.04 PC.
Installation
Follow the Indigo installation instruction here. (note: if you are on an ARM, follow the Ubuntu amdf link)
Navigating ROS File Systems
rospack - help find information on available packages rospack find [package name] Example: % rospack find roscpp /opt/ros/indigo/share/roscpp
roscd - change the current directory to a package or a stack Example: % roscd roscpp % pwd YOUR_INSTALL_PATH/share/roscpp
rosls - list contents of a package or a stack Example: % rosls roscpp_tutorials cmake launch package.xml srv
Creating a Package
ROS software stack is composed of packages. To create a package, first change the current directory to the ‘src’ directory of your catkin workspace, then do the following:
% catkin_create_pkg beginner_tutorials std_msgs rospy roscpp
The first argument is your new package name, the next three are declared package dependencies.
Package Dependencies
Package dependencies can be identified by using the rospack command:
% rospack depends roscpp cpp_common rostime ... xmlrpcpp
Customize the package.xml
The package.xml inside the newly created package is the manifest, initially containing auto-generated informations. Package author should edit package.xml to reflect correct information.
Build ROS Packages
ROS packages can be built collectively at the workspace level. First source the setup.bash file. You should have already added this to your ~/.bashrc in the first step. Now follow the below example:
% catkin_make
ROS Nodes
ROS runtime is made of nodes. Each node is a separate running thread. A special node is the Master, which is invoked by:
% roscore
A node advertises its Services and Parameters to the master, as well topics it publishes or subscribes to. A topic is a data object serialized as an IP message.
% rosnode list # list all the nodes % rosnode info /rosout # returns information about a specific node (rosout) % rosrun turtlesim turtlesim_node # run turtlesim executable name 'turtlesim_node' % rosnode ping my_turtle # ping a node
Using rqt_graph and rq_plot
rqt_graph is a dynamic graphing tool that shows whats going on in a ROS system. To install it, simply:
% sudo apt-get install ros-indigo-rqt % sudo apt-get install ros-indigo-rqt-common-plugins
To run rqt_graph, enter:
% rosrun rqt_graph rqt_graph
rqt_plot displays scrolling time plot of data published any topic. To run it simply:
% rosrun rqt_plot rqt_plot
ROS Topics
ROS topics are messages, or information that nodes can publish or subscribe to. rostopic is the too that allows one to get information about ROS topics.
% rostopic -h # help % rostopic bw [topic] # display bandwidth used by topics % rostopic echo [topic] # print messages to screen % rostopic hz [topic] # display publishing rate of a topic % rostopic pub [topic] # publish data to a topic % rostopic type [topic] # print topic type
ROS Services
ROS services exposes remote procedure call interfaces so other nodes can call the interface as a service. rosservice is the tool that provides information to the service:
% rosservice list # print information about active services % rosservice call [service] [args] # call the service with the provided args % rosservice type [service] # print service type % rosservice find [service type] # find services by service type % rosservice uri # print service ROSRPC uri
ROS Parameters
rosparam is used to access the published parameters.
% rosparam list # list all the parameters % rosparam set [param] [value] # set parameter value % rosparam get [param] # get parameter value % rosparam dump [file_name] [opt namespace] # dump parameter to a file % rosparam load [file_name] [opt namespace] # load parameter from a file
Creating Message
To implement a message, first create the ‘msg’ directory and place in it a *.msg file. For example,
% mkdir msg % echo "int64 num" > msg/Num.msg
Now export the message runtime dependency by editing the CMakeList.txt file in the ‘src’ directory:
catkin_package( ... CATKIN_DEPENDS message_runtime ... ...)
Now find also the add_message_files{} block and remove the ‘#’ and add the message file Num.msg just created, like this:
add_message_files( FILES Num.msg )
Next, uncomment the generate_messages() block, like this:
generate_messages( DEPENDENCIES std_msgs )
The created message can be checked using the rosmsg tool, for example:
% rosmsg show beginner_tutorials/Num
Creating a Service
To create a service, first create a directory called ‘srv’. Then the easiest way to create a *.srv file is copy from an existing package:
# roscp [package_name] [file_to_copy_path] [copy_path] % roscp rospy_tutorials AddTwoInts.srv srv/AddTwoInts.srv
Now make sure the message is generated and used at runtime by commenting in the below two lines:
<build_depend>message_generation</build_depend> <run_depend>message_runtime</run_depend>
Now, as in message, check CMakeList.txt to make sure message_generation is added to the find_package() block, as shown below:
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation )
and add the *.srv files to the add_service_files() block:
add_service_files( FILES AddTwoInts.srv )
Now as with message, comment in the generate_message() block, if it wasn’t done earlier:
generate_messages( DEPENDENCIES std_msgs )
Now to check if you added the service properly, try:
# rossrv show <service type> % rossrv show beginner_tutorials/AddTwoInts [beginner_tutorials/AddTwoInts]: int64 a int64 b --- int64 sum [rospy_tutorials/AddTwoInts]: int64 a int64 b --- int64 sum %
Creating a Publisher/Subscriber Node in Python
Python script for creating a listener looks like the code below. Put the code into the file, add_two_ints_server.py:
#!/usr/bin/env python from beginner_tutorials.srv import * 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()
The client code that makes use of the serivce looks like this:
#!/usr/bin/env python 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, 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))
Creating a Publisher/Subscriber Node in C++
Below is an example of a talker node that sends a “chatter” message:
#include "ros/ros.h" #include "std_msgs/String.h" #include /** * 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("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; }
The listener code looks like this:
#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; }