36 PKG =
'khi_robot_test' 37 import roslib; roslib.load_manifest(PKG)
44 import geometry_msgs.msg
47 if rospy.has_param(
'/test_group_name'):
48 gn =
'/' + rospy.get_param(
'/test_group_name')
51 service = gn +
'/khi_robot_command_service' 54 rospy.wait_for_service(service)
56 khi_robot_command_service = rospy.ServiceProxy(service,KhiRobotCmd)
57 resp1 = khi_robot_command_service(type_arg, cmd_arg)
59 except rospy.ServiceException, e:
60 rospy.loginfo(
'Service call failed: %s', e)
72 self.assertEqual(
'HOLDED', ret.cmd_ret)
78 self.assertEqual(0, int(ret.cmd_ret))
80 self.assertEqual(
'INACTIVE', ret.cmd_ret)
86 self.assertEqual(-1, int(ret.cmd_ret))
88 self.assertEqual(
'INACTIVE', ret.cmd_ret)
94 self.assertEqual(
'ACTIVE', ret.cmd_ret)
98 offset = [0, 2000, 2000]
103 for i
in range(size):
105 rospy.loginfo(
'SIGNAL %d', i+1+offset[j])
107 set_cmd =
'set_signal ' + str(i+1+offset[j])
109 get_cmd =
'get_signal ' + str(i+1+offset[j])
111 self.assertEqual(
'-1', ret.cmd_ret)
114 set_cmd =
'set_signal -' + str(i+1+offset[j])
116 get_cmd =
'get_signal ' + str(i+1+offset[j])
118 self.assertEqual(
'0', ret.cmd_ret)
123 self.assertEqual(1, int(ret.cmd_ret))
125 if __name__ ==
'__main__':
127 rospy.init_node(
"test_khi_robot_control_node")
129 rostest.rosrun(PKG,
'test_khi_robot_control', TestKhiRobotControl)
def cmdhandler_client(type_arg, cmd_arg)