test_rospy_api.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 import os
00035 import sys
00036 import struct
00037 import unittest
00038 import time
00039 
00040 # test rospy API verifies that the rospy module exports the required symbols
00041 class TestRospyApi(unittest.TestCase):
00042 
00043     def test_msg(self):
00044         # rospy.Message really only exists at the client level, as the internal
00045         # implementation is built around the roslib reference, so we put the test here
00046 
00047         import rospy
00048         #trip wires against Message API
00049         m = rospy.Message()
00050         try:
00051             from cStringIO import StringIO
00052         except ImportError:
00053             from io import StringIO
00054         buff = StringIO()
00055         m.serialize(buff)
00056         self.assertEquals(0, buff.tell())
00057         m.deserialize('')
00058         
00059     def test_anymsg(self):
00060         # rospy.AnyMsg really only exists at the client level as nothing within
00061         # rospy uses its functionality.
00062         
00063 
00064         try:
00065             from cStringIO import StringIO
00066         except ImportError:
00067             from io import StringIO
00068         import rospy
00069         #trip wires against AnyMsg API
00070         m = rospy.AnyMsg()
00071         try:
00072             m.serialize(StringIO())
00073             self.fail("AnyMsg should not allow serialization")
00074         except:
00075             pass
00076 
00077         teststr = 'foostr-%s'%time.time()
00078         m.deserialize(teststr)
00079         self.assertEquals(teststr, m._buff)
00080 
00081         #test AnyMsg ctor error checking
00082         try:
00083             m = rospy.AnyMsg('foo')
00084             self.fail("AnyMsg ctor should not allow args")
00085         except: pass
00086 
00087     def test_rospy_api(self):
00088         import rospy
00089 
00090         # just a laundry list of API methods to make sure that they still exist
00091         
00092         # removed
00093         try:
00094             rospy.add_shutdown_hook
00095             self.fail("add_shutdown_hookshould not longer be top-level API")
00096         except AttributeError: pass
00097 
00098         rospy.DEBUG
00099         rospy.INFO
00100         rospy.WARN
00101         rospy.ERROR
00102         rospy.FATAL
00103         
00104         rospy.get_caller_id
00105         rospy.get_name        
00106         rospy.get_master
00107         rospy.get_namespace
00108         rospy.get_published_topics
00109         rospy.get_node_uri
00110         rospy.get_ros_root
00111         rospy.get_time
00112         rospy.get_rostime
00113         rospy.init_node
00114         rospy.is_shutdown
00115         rospy.logdebug
00116         rospy.logerr
00117         rospy.logfatal
00118         rospy.loginfo        
00119         rospy.logout #deprecated
00120         rospy.logwarn
00121         rospy.logdebug_throttle
00122         rospy.logerr_throttle
00123         rospy.logfatal_throttle
00124         rospy.loginfo_throttle
00125         rospy.logwarn_throttle
00126         rospy.myargv
00127         rospy.on_shutdown
00128         rospy.parse_rosrpc_uri
00129         rospy.resolve_name
00130         rospy.remap_name
00131         rospy.signal_shutdown
00132         rospy.sleep
00133         rospy.spin
00134         rospy.wait_for_message
00135         rospy.wait_for_service
00136 
00137         rospy.delete_param
00138         rospy.get_param
00139         rospy.get_param_names
00140         rospy.has_param
00141         rospy.set_param
00142         rospy.search_param        
00143 
00144         rospy.AnyMsg
00145         rospy.Duration
00146         rospy.Header
00147         rospy.MasterProxy
00148         rospy.Message
00149         rospy.Publisher
00150         rospy.Rate
00151         rospy.ROSException
00152         rospy.ROSInternalException
00153         rospy.ROSSerializationException
00154         rospy.ServiceException
00155         rospy.Service
00156         rospy.ServiceProxy
00157         rospy.SubscribeListener
00158         rospy.Subscriber        
00159         rospy.Time
00160         rospy.TransportException
00161         rospy.TransportTerminated
00162         rospy.TransportInitError


test_rospy
Author(s): Ken Conley
autogenerated on Thu Jun 6 2019 21:10:57