[Documentation] [TitleIndex] [WordIndex

rospy/2008-09-18 rospy Specification Review

Package Developer: KenConley

Reviewers:

Agenda

The focus of this review will be going over the rospy client API for writing services and nodes. In particular:

Please add your questions/answers here:

Package Specification

A canonical rospy publisher:

   1 import rostools; rostools.update_path('rospy_demo')
   2 
   3 import sys
   4 import time
   5 import rospy
   6 from std_msgs.msg import String
   7 
   8 def talker():
   9     pub = rospy.TopicPub("chatter", String)
  10     rospy.ready('talker', anonymous=True)
  11     count = 0
  12     while not rospy.is_shutdown():
  13         pub.publish(String("hello world %d"%count))
  14         count += 1
  15         time.sleep(0.01)
  16         
  17 if __name__ == '__main__':
  18     try:
  19         talker()
  20     except KeyboardInterrupt, e:
  21         pass
  22     print "exiting"

A canonical rospy listener:

   1 import rostools; rostools.update_path('rospy_demo')
   2 
   3 import sys
   4 import rospy
   5 from std_msgs.msg import String
   6 
   7 def callback(data):
   8     print rospy.get_caller_id(), "I heard %s"%data.data
   9     
  10 def listener():
  11     rospy.ready('listener')
  12     rospy.TopicSub("chatter", String, callback)
  13     rospy.spin()
  14         
  15 if __name__ == '__main__':
  16     listener()

A canonical rospy service

   1 import rostools; rostools.update_path('rospy_tutorials')
   2 
   3 from rospy_tutorials.srv import *
   4 import rospy 
   5 
   6 def add_two_ints(req):
   7     return AddTwoIntsResponse(req.a + req.b)
   8 
   9 def add_two_ints_server():
  10     rospy.ready('add_two_ints_server')
  11     s = rospy.Service('add_two_ints', AddTwoInts, add_two_ints)
  12     s.register()
  13     rospy.spin()
  14 
  15 if __name__ == "__main__":
  16     add_two_ints_server()

A canonical rospy service client:

   1 import rostools; rostools.update_path('rospy_tutorials')
   2 
   3 import sys
   4 import os
   5 import rospy
   6 from rospy_tutorials.srv import *
   7 
   8 def add_two_ints_client(x, y):
   9     rospy.wait_for_service('add_two_ints')
  10     try:
  11         add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
  12         # simplified style
  13         resp1 = add_two_ints(x, y)
  14         # formal style
  15         resp2 = add_two_ints.call(AddTwoIntsRequest(x, y))
  16         return resp1.sum
  17     except rospy.ServiceException, e:
  18         print "Service call failed: %s"%e
  19 
  20 if __name__ == "__main__":
  21     add_two_ints_client(random.randint(-50000, 50000), random.randint(-50000, 50000))

Key features

Dependencies

Testing strategy

Minutes

TODO:

Post-meeting addendums:

Conclusion

NEEDS MORE WORK.

Work on TODOs and schedule another 1/2 hour meeting.



2024-11-16 17:44