9 import roslib; roslib.load_manifest(PKG)
11 import unittest, os, sys, time, rospy
13 from omniORB
import CORBA, any, cdrUnmarshal, cdrMarshal
17 import RTC, OpenRTM, SDOPackage, RTM
27 print "configuration ORB with ", nshost,
":", nsport
28 os.environ[
'ORBInitRef'] =
'NameService=corbaloc:iiop:{0}:{1}/NameService'.format(nshost,nsport)
31 orb = CORBA.ORB_init(sys.argv, CORBA.ORB_ID)
32 nameserver = orb.resolve_initial_references(
"NameService");
33 rootnc = nameserver._narrow(CosNaming.NamingContext)
34 except omniORB.CORBA.ORB.InvalidName, e:
35 sys.exit(
'[ERROR] Invalide Name (hostname={0}).\n'.format(nshost) +
36 'Make sure the hostname is correct.\n' + str(e))
37 except omniORB.CORBA.TRANSIENT, e:
38 sys.exit(
'[ERROR] Connection Failed with the Nameserver (hostname={0} port={1}).\n'.format(nshost, nsport) +
39 'Make sure the hostname is correct and the Nameserver is running.\n' + str(e))
40 except Exception
as e:
50 nc = rootnc.resolve([CosNaming.NameComponent(name,
"rtc")])
52 print >>sys.stderr,
"Waiting for %s ..."%name
56 print >>sys.stderr,
"Found for %s (%r)"%(name,nc)
65 print >>sys.stderr,
"initCORBA" 69 print >>sys.stderr,
"wait for MyServiceROSBridge" 70 bridge =
findObject(
"MyServiceROSBridge")._narrow(RTC.RTObject)
71 print >>sys.stderr,
"wait for MyServiceProvider" 72 provider =
findObject(
"MyServiceProvider0")._narrow(RTC.RTObject)
74 print >>sys.stderr,
"connect components" 75 inP = provider.get_ports()[0]
76 outP = bridge.get_ports()[0]
77 con_prof = RTC.ConnectorProfile(
"connector0",
"", [outP, inP], [])
80 print >>sys.stderr,
"activate components" 81 bridge.get_owned_contexts()[0].activate_component(bridge)
82 provider.get_owned_contexts()[0].activate_component(provider)
87 rospy.init_node(
'test_compile_idl')
91 sys.path.append(
"/tmp/test_compile_idl/devel/lib/python2.7/dist-packages")
93 import rtmbuild_test.srv
94 rospy.logwarn(
"wait for service")
95 rospy.wait_for_service(
"/MyServiceROSBridge/echo")
96 echo = rospy.ServiceProxy(
"/MyServiceROSBridge/echo", rtmbuild_test.srv.SimpleService_MyService_echo)
97 req = rtmbuild_test.srv.SimpleService_MyService_echo
98 msg =
"this is test data 123" 99 rospy.logwarn(
"send request > " + msg)
101 rospy.logwarn(
"check return < " + res.operation_return)
102 self.assertTrue(res.operation_return == msg,
"SimpleService.echo returns incorrect string")
105 if __name__ ==
'__main__':
107 rostest.rosrun(PKG,
'test_myservice_rosbridge', TestCompileIDL)