3 """! @file test_cluedo_armor_interface.py
5 @brief testing the node cluedo_armor_interface.cpp
7 @authors Francesco Ganci (S4143910)
10 This node implements a simple test for the node cluedo_armor_interface.cpp :
11 try a simple reasoning process using the interface.
13 @see test_cluedo_armor_interface.launch launch file for the test
18 from robocluedo_msgs.srv
import AddHint, AddHintRequest, AddHintResponse
19 from robocluedo_msgs.srv
import FindConsistentHypotheses, FindConsistentHypothesesRequest, FindConsistentHypothesesResponse
20 from robocluedo_msgs.msg
import Hypothesis
21 from robocluedo_msgs.srv
import DiscardHypothesis, DiscardHypothesisRequest, DiscardHypothesisResponse
22 from std_srvs.srv
import Trigger, TriggerRequest, TriggerResponse
24 client_name_add_hint =
"/cluedo_armor/add_hint"
25 client_add_hint =
None
27 client_name_find_consistent_h =
"/cluedo_armor/find_consistent_h"
28 client_find_consistent_h =
None
30 client_name_wrong_h =
"/cluedo_armor/wrong_hypothesis"
33 client_name_backup =
"/cluedo_armor/backup"
37 test_name =
"test_cluedo_armor_interface"
40 global client_add_hint
41 global client_find_consistent_h
45 rospy.loginfo(
"[%s] formulating hypothesis : %s(where:%s, what:%s, who:%s)", test_name,
"HP1",
"study",
"knife",
"mark" )
50 rospy.loginfo(
"[%s] expected 1 consistent hypothesis", test_name )
51 rospy.loginfo(
"[%s] asking for consistent hypotheses... ", test_name )
53 rospy.loginfo(
"[%s] received size : %d ", test_name, len(hplist) )
54 rospy.loginfo(
"[%s] -> %s(where:%s, what:%s, who:%s)", test_name, hplist[0].tag, hplist[0].where, hplist[0].what, hplist[0].who )
56 rospy.loginfo(
"[%s] discarding the hypothesis... ", test_name )
57 wrong_h_msg = DiscardHypothesisRequest( )
58 wrong_h_msg.hypothesisTag = hplist[0].tag
60 rospy.loginfo(
"[%s] asking again for consistent hypotheses... ", test_name )
62 rospy.loginfo(
"[%s] received size (expected 0) : %d ", test_name, len(hplist) )
64 rospy.loginfo(
"[%s] saving ontology... ", test_name )
66 rospy.loginfo(
"[%s] OK!", test_name )
82 rospy.loginfo(
"[%s] closing...", test_name )
87 if __name__ ==
"__main__":
88 rospy.init_node( test_name )
89 rospy.on_shutdown( on_shut_msg )
92 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_add_hint )
93 rospy.wait_for_service( client_name_add_hint )
94 client_add_hint = rospy.ServiceProxy( client_name_add_hint, AddHint )
95 rospy.loginfo(
"[%s] OK!", test_name )
98 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_find_consistent_h )
99 rospy.wait_for_service( client_name_find_consistent_h )
100 client_find_consistent_h = rospy.ServiceProxy( client_name_find_consistent_h, FindConsistentHypotheses )
101 rospy.loginfo(
"[%s] OK!", test_name )
104 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_wrong_h )
105 rospy.wait_for_service( client_name_wrong_h )
106 client_wrong_h = rospy.ServiceProxy( client_name_wrong_h, DiscardHypothesis )
107 rospy.loginfo(
"[%s] OK!", test_name )
110 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_backup )
111 rospy.wait_for_service( client_name_backup )
112 client_backup = rospy.ServiceProxy( client_name_backup, Trigger )
113 rospy.loginfo(
"[%s] OK!", test_name )