From 859cf64488a858fab757c814d4835e321bbf8448 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Sun, 9 Nov 2014 21:07:59 +0900 Subject: [PATCH] add test code for multibyte string --- test/test_roscpp/test/src/service_call.cpp | 13 +++++++++++ .../test/rostest/test_basic_services.py | 23 +++++++++++++++++++ 2 files changed, 36 insertions(+) diff --git a/test/test_roscpp/test/src/service_call.cpp b/test/test_roscpp/test/src/service_call.cpp index b50869af21..6e05ab4f17 100644 --- a/test/test_roscpp/test/src/service_call.cpp +++ b/test/test_roscpp/test/src/service_call.cpp @@ -58,6 +58,19 @@ TEST(SrvCall, callSrv) ASSERT_STREQ(res.str.c_str(), "CASE_flip"); } +TEST(SrvCall, callSrvUnicode) +{ + test_roscpp::TestStringString::Request req; + test_roscpp::TestStringString::Response res; + + req.str = std::string("ロボット"); + + ASSERT_TRUE(ros::service::waitForService("service_adv")); + ASSERT_TRUE(ros::service::call("service_adv", req, res)); + + ASSERT_STREQ(res.str.c_str(), "ロボット"); +} + TEST(SrvCall, callSrvMultipleTimes) { test_roscpp::TestStringString::Request req; diff --git a/test/test_rospy/test/rostest/test_basic_services.py b/test/test_rospy/test/rostest/test_basic_services.py index dda4d402aa..14900fd2df 100755 --- a/test/test_rospy/test/rostest/test_basic_services.py +++ b/test/test_rospy/test/rostest/test_basic_services.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +# -*- coding: utf-8 -*- # Software License Agreement (BSD License) # # Copyright (c) 2008, Willow Garage, Inc. @@ -213,6 +214,28 @@ def test_String_String(self): resp_req_kwds = self._test_req_kwds(name, Cls, {'str': String('FOO'), 'str2': Val('bar')}) for resp in [resp_req, resp_req_naked, resp_req_kwds]: self.assertEquals('FOObar', resp.str.data) + + def test_String_String_unicode(self): + from std_msgs.msg import String + from test_rospy.srv import StringString, StringStringRequest + from test_rospy.msg import Val + import sys + Cls = StringString + Req = StringStringRequest + + for name in [STRING_CAT_SERVICE_NAKED, STRING_CAT_SERVICE_WRAPPED]: + if sys.version_info.major < '3': + resp_req = self._test(name, Cls, Req(String(u'ロボット'), Val(u'机器人'))) + resp_req_naked = self._test_req_naked(name, Cls, (String(u'ロボット'), Val(u'机器人'),)) + resp_req_kwds = self._test_req_kwds(name, Cls, {'str': String(u'ロボット'), 'str2': Val(u'机器人')}) + for resp in [resp_req, resp_req_naked, resp_req_kwds]: + self.assertEquals('ロボット机器人', resp.str.data) # if you send in unicode, you'll receive in str + else: + resp_req = self._test(name, Cls, Req(String('ロボット'), Val('机器人'))) + resp_req_naked = self._test_req_naked(name, Cls, (String('ロボット'), Val('机器人'),)) + resp_req_kwds = self._test_req_kwds(name, Cls, {'str': String('ロボット'), 'str2': Val('机器人')}) + for resp in [resp_req, resp_req_naked, resp_req_kwds]: + self.assertEquals('ロボット机器人', resp.str.data) def test_constants(self): Cls = ConstantsMultiplex