Note: This tutorial assumes that you have completed the previous tutorials: Interacting with your Turtlebot, Customising the Turtle. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Create your First Rapp
Description: Create, load and execute a 'babbler' rapp, and, is it really worth the effort?Keywords: turtlebot rapp
Tutorial Level: BEGINNER
Next Tutorial: Create your First Interaction
Create, load and execute your first rapp, and, is it really worth the effort? |
Goal
Our goal here is to create your first managed application (rapp) for the turtlebot, load it and then finally execute. To keep things simple, we'll just call the default talker node and remap it so that it talks on /babbler.
Tip: this tutorial doesn't actually need to be run on the turtlebot - can run on the pc whilst the kobuki driver rolls over looking for a connection. |
Getting Dirty
Create
In your source workspace, let's create a package:
> catkin_create_pkg my_rapps_tutorial > mkdir -p my_rapps_tutorial/apps/babbler my_rapps_tutorial/scripts
Create the following files which will make up our rapp (informative comments included inline in the files):
1 #!/usr/bin/env python
2
3 import rospy
4 from std_msgs.msg import String
5
6 def talker():
7 rospy.init_node('talker', anonymous=True)
8
9 message = rospy.get_param('~message', 'hello world')
10 freq = rospy.get_param('~frequency', 10)
11 topic_name = rospy.get_param('~topic_name', 'babbler')
12 pub = rospy.Publisher(topic_name, String, queue_size=10)
13
14 r = rospy.Rate(freq) # 10hz
15
16 while not rospy.is_shutdown():
17 str = "%s %s"%(message, rospy.get_time())
18 rospy.loginfo(str)
19 pub.publish(str)
20 r.sleep()
21
22 if __name__ == '__main__':
23 try:
24 talker()
25 except rospy.ROSInterruptException: pass
1 <launch>
2 <!--
3 Rapp launchers have nothing special that would otherwise indicate they are
4 'rapps', or even entities that are capable of being multi-mastered.
5 -->
6 <!--
7 Args are the means the app manager passes in parameters to rapps.
8 Think of them as the 'public parameters' of a rapp.
9
10 Typically for any launcher there are only a couple of variables that
11 the user really wants to tweak. This is generally a good practice when
12 designing launchers anyway. If there are really alot, think of passing
13 in an arg pointing to a custom yaml configuration file.
14
15 Make sure these args and their defaults are reflected in the public
16 parameters file (babbler.parameters). When launching from inside the
17 app manager, the public parameters override what's here, but the settings
18 here are useful if you ever choose to do testing with this launch file
19 on its own.
20 -->
21 <arg name="message" default="hello world" doc="hello world string"/>
22 <arg name="frequency" default="10" doc="frequency of publishing in Hz"/>
23 <!-- This is not the only way to do remapping, but it does provide flexibility -->
24 <arg name="topic_name" default="babbler" doc="remap the topic name by parameter"/>
25 <node name="babbler" pkg="my_rapps_tutorial" type="babbler.py" required="true">
26 <param name="topic_name" value="$(arg topic_name)"/>
27 <param name="message" value="$(arg message)"/>
28 <param name="frequency" value="$(arg frequency)"/>
29 </node>
30 </launch>
1 # These specify the public parameters and their default values. These
2 # should also be reflected as args with their respective defaults in the launcher.
3 # The app manager checks against these and denies/accepts incoming parameters
4 # received when calling the start_rapp service. They also get used as idl info
5 # for the rapp.
6 #
7 # Note: it is easier and more reliable to have them set here in yaml than have to parse
8 # and extract information from arg tags in the launcher.
9 #
10 topic_name: babbler
11 message: hello world
12 frequency: 10
1 # these highlight the public interfaces of the rapp - useful for idl introspection, but
2 # also enable the rapp for multimaster purposes should you so wish (these
3 # topics/services/actions automatically get flipped across to a connected master
4 # when the rapp starts
5 #
6 publishers:
7 - name: babbler
8 type: std_msgs/String
9 # not necessary to add if empty, but for sake of completeness
10 subscribers: []
11 services: []
12 action_clients: []
13 action_servers: []
1 #
2 # This is the file that binds it all together along with some extra meta-information.
3 # Note, any links here are relative to this file.
4 #
5 # Display name for guis when displaying this rapp amongst others.
6 display: Babbler
7 # Human readable description of the rapp.
8 description: Turtlebot babbler tutorial.
9 # The compatibility flag classifies how portable a rapp can be.
10 #
11 # If a rapp is loaded into an app manager with an compatible rocon uri, then it will
12 # reject the app (e.g. you put an indigo rapp on a hydro app manager, or a turtlebot
13 # specific rapp on a pr2).
14 #
15 # This is only really important if you're sharing your rapps around many robots.
16 # If you're just testing a rapp on a single robot, having the default `rocon:/` setting
17 # makes it promiscuous. See http://docs.ros.org/indigo/api/rocon_uri/html/ for
18 # more information on rocon_uri rules.
19 #
20 compatibility: rocon:/
21 launch: babbler.launch
22 public_interface: babbler.interface
23 public_parameters: babbler.parameters
24 # If you drop an icon here it will use that,
25 # otherwise it will use a default icon
26 # icon: babbler.png
You'll also need to make sure the babbler script is executable:
> chmod 755 my_rapps_tutorial/scripts/babbler.py
and touch my_rapps_tutorial/CMakelists.txt so that it is installed:
install(PROGRAMS scripts/babbler.py DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
Finally, you need to export the rapp in my_rapps_tutorial/package.xml by adding the element:
<export> <rocon_app>apps/babbler/babbler.rapp</rocon_app> </export>
Verify
Rebuild, and if all went well, you should now be able to discover it on the command line:
> rocon_app list Resource: my_rapps_tutorial/babbler - Compatibility : rocon:/ - Ancestor : my_rapps_tutorial/babbler
and get info about it:
> rocon_app info my_rapps_tutorial/babbler Displays rapp resolved information == my_rapps_tutorial/babbler - Implementation Ancestor == description : Turtlebot babbler tutorial. launch : /opt/turtlebot/src/my_rapps_tutorial/apps/babbler/babbler.launch public_parameters : {'message': 'hello world', 'topic_name': 'babbler', 'frequency': 10} display : Babbler public_interface : {'services': [], 'publishers': [{'type': 'std_msgs/String', 'name': 'babbler'}], 'action_clients': [], 'subscribers': [], 'action_servers': []} compatibility : rocon:/
and even run the launcher:
> roslaunch my_rapps_tutorial babbler.launch --screen
Load
The next goal is to make sure this rapp gets loaded by the turtlebot app manager. On the turtlebot (after sourcing your setup.bash) you should find the following environment variable defined:
> env | grep TURTLEBOT_RAPP_ TURTLEBOT_RAPP_PACKAGE_WHITELIST=[rocon_apps, turtlebot_rapps] TURTLEBOT_RAPP_PACKAGE_BLACKLIST=[]
Here you can see the turtle has loaded two packages' rapps already. We're going to add our package by exporting:
> export TURTLEBOT_RAPP_PACKAGE_WHITELIST="[rocon_apps, turtlebot_rapps, my_rapps_tutorial]"
Restart the turtle:
> roslaunch turtlebot_bringup minimal.launch --screen ..... [INFO] [WallTime: 1426502367.475830] Rapp Manager : 'my_rapps_tutorial/babbler' added to the list of runnable apps. .....
Call the app manager service to see if it loaded:
> rosservice call /app_manager/list_rapps | grep my_rapps_tutorial
Execute
Service calls to start apps require three arguments:
Rapp Name: in package/rapp format.
Remappings: like any remappings you'd provide inside a launch file
Parameters: values specified in the .parameters file that go in via launch args.
# Start > rosservice call /app_manager/start_rapp my_rapps_tutorial/babbler [] [] # Stop > rosservice call /app_manager/stop_rapp # Remap the default babbler topic via a remapping rosservice call /app_manager/start_rapp my_rapps_tutorial/babbler ['{remap_from: babbler, remap_to: natter}'] [] > rosservice call /app_manager/stop_rapp # Remap the default babbler topic via the topic_name parameter > rosservice call /app_manager/start_rapp my_rapps_tutorial/babbler [] ['{key: topic_name, value: natter}'] > rosservice call /app_manager/stop_rapp # Different message > rosservice call /app_manager/start_rapp my_rapps_tutorial/babbler [] ['{key: message, value: dudes}'] > rosservice call /app_manager/stop_rapp
Tip: only one rapp may run at a time, design these like 'tasks' for the robot - this is intentionally simplified so you don't run into a resource conflict nightmare. |
Is it Worth The Effort?
Above and beyond doing regular roslaunchers, is the generation of a few extra files as outlined above worth the effort?
2 Sided Interactions
The real power of the application manager comes when working with the interactions framework (proceed with the next tutorial). Here we bring up/tear down only the robot side software - with interactions we finally enabout bringup/tear down of both robot and pc software simultaneously.
For the users/testers/demonstrators
All of this is mostly academic for the dev who is quite happy to use launchers most of the time. Working with a gui to do the application management above (the remocons) can be a nice convenience to avoid the tedium of opening/closing multiple ssh terminals.
Where it is eminently useful is when you want testers/users/demonstrators to run your applications and both you and your users do not want to find/write/read a long recipe of instructions that may or may not be exactly up to date, nor use command line terminals to do everything. Instead, they need only fire up a remocon - everything that you have prepared for them is at their fingertips - documentation links, 1 and 2 sided interactions, and you have a better guarantee that everything is up to date as this is delivered to the user by the running instance.
Hooks into capabilities
Although not illustrated here, rapps also have the ability to specify dependencies to capabilities very simply and easily via yaml. This avoids to need use of any programming to start/stop capabilities, greatly reduces the size of your launch files and also allows your rapps to be truly portable across robots.
Unique Namespaces
When running multiple robots (esp. if multi-mastering) it is imperative that launched applications run in a unique namespace so that conflicts do not occur. The app manager, if flagged, will push your application launcher down into a uniquely generated namespace. This keeps your launchers free of any namespacing clutter.
Start the turtlebot ready for multimastering (~minimal.launch for multimaster):
> roslaunch turtlebot_bringup concert_client.launch --screen
At this point the app manager reconfigures itself with a unique namespace by postfixing a uuid to the end of its robot name. All apps are pushed down into this namespace. In another shell:
> rosservice list | grep start_rapp > rosservice call /turtlebot7309db4720554adeb43c5d1707c03f4a/start_rapp my_rapps_tutorial/babbler [] [] > rostopic list | grep babbler /turtlebot7309db4720554adeb43c5d1707c03f4a/babbler
If you wish to avoid uuid's and just guarantee unique namespaces yourself, just disable the uuid prefixing and set your own robot name:
> roslaunch turtlebot_bringup concert_client.launch robot_name:=bob robot_unique_name:=false --screen
Multimaster
Application managers can be invited by other masters. This gives a control master the ability to parameterise, start and stop rapps on the robot from a central workspace. When the app is started, the rapp's public interface (pubs, subs, services, actions) will automatically register on the control master allowing multimaster nodes. This operation will be covered in a more advanced tutorial.
What Next?
Create your First Interaction or return to TurtleBot main page.