#################################### ##FILL ME IN #################################### ## links to any required tutorials ## note.0= [[actionlib_tutorials/Tutorials/SimpleActionClient(Threaded)|writing a threaded simple action client]] ## descriptive title for the tutorial ## title = Running an Action Server and Client with Other Nodes ## multi-line description to be displayed in search ## description = This tutorial covers running the averaging action server and client with another data node then visualizing the channel output and node graph. ## the next tutorial description ## next = ## links to next tutorial ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory #################################### <> <> <> <> == Writing the Data Node == Before running the action server and client a data node needs to be created. Create actionlib_tutorials/scripts/gen_numbers.py in your favorite editor, and place the following inside it: {{{{#!wiki buildsystem rosbuild {{{ #!python #!/usr/bin/env python import roslib; roslib.load_manifest('actionlib_tutorials') import rospy from std_msgs.msg import Float32 import random def gen_number(): pub = rospy.Publisher('random_number', Float32) rospy.init_node('random_number_generator', log_level=rospy.INFO) rospy.loginfo("Generating random numbers") while not rospy.is_shutdown(): pub.publish(Float32(random.normalvariate(5, 1))) rospy.sleep(0.05) if __name__ == '__main__': try: gen_number() except Exception, e: print "done" }}} }}}} {{{{#!wiki buildsystem catkin {{{ #!python #!/usr/bin/env python import rospy from std_msgs.msg import Float32 import random def gen_number(): pub = rospy.Publisher('random_number', Float32) rospy.init_node('random_number_generator', log_level=rospy.INFO) rospy.loginfo("Generating random numbers") while not rospy.is_shutdown(): pub.publish(Float32(random.normalvariate(5, 1))) rospy.sleep(0.05) if __name__ == '__main__': try: gen_number() except Exception, e: print "done" }}} }}}} The above code generates random numbers with a normal distribution centered around 5 with a standard deviation of 1 and publishes the numbers on the /random_number topic. Don't forget to make the node executable: {{{ chmod +x gen_numbers.py }}} == Start the Data Node == Start by bringing up the roscore in a new terminal: {{{ $ roscore }}} Now start the data node in a new terminal: {{{ rosrun actionlib_tutorials gen_numbers.py }}} You will see: {{{ Generating random numbers }}} == Viewing the Action Feedback == In a new terminal, rostopic the feedback channel to see the feedback from the action server: {{{ $ rostopic echo /averaging/feedback }}} While the server is acting on the goal you will see something similar to: {{{ --- header: seq: 1 stamp: 1251489509536852000 frame_id: status: goal_id: stamp: 1251489509511553000 id: 1251489509.511553000 status: 1 text: feedback: sample: 1 data: 3.96250081062 mean: 3.96250081062 std_dev: 0.000687940046191 --- header: seq: 2 stamp: 1251489509588828000 frame_id: status: goal_id: stamp: 1251489509511553000 id: 1251489509.511553000 status: 1 text: feedback: sample: 2 data: 5.16988706589 mean: 4.56619405746 std_dev: 0.60369348526 --- }}} == Viewing the Action Result == In a new terminal, rostopic the feedback channel to see the feedback from the action server: {{{ $ rostopic echo /averaging/result }}} After the goal is completed you will see something similar to: {{{ --- header: seq: 1 stamp: 1251489786993936000 frame_id: status: goal_id: stamp: 1251489781746524000 id: 1251489781.746524000 status: 4 text: result: mean: 4.99936008453 std_dev: 1.10789334774 }}} == Viewing the Action Node Graph == Alternatively you can look at the nodes: {{{{{#!wiki version fuerte_and_older {{{ $ rxgraph & }}} }}}}} {{{{{#!wiki version groovy_and_newer {{{ $ rosrun rqt_graph rqt_graph & }}} }}}}} {{attachment:averaging_client_server.png||width=100%}} == Start the Client and Server == Start the action server in a new terminal: {{{ $ rosrun actionlib_tutorials averaging_server }}} When the action has completed it will print out an info message which may be succeeded or aborted depending on the random data sampled. {{{ [ INFO] 1251489514.736936000: /averaging: Aborted }}} And then run the action client in a new terminal: {{{ $ rosrun actionlib_tutorials averaging_client }}} When the client receives notification of the completion of the goal it will also print out an info message with the result of the action: {{{ [ INFO] 1251489514.737339000: Action finished: ABORTED }}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE