3 """! @file test_oracle_plus_interface.py
5 @brief testing the nodes cluedo_oracle.cpp and cluedo_armor_interface.cpp
7 @authors Francesco Ganci (S4143910)
10 Each time an hint arrives, store it into the ontology.
12 @see test_cluedo_oracle_plus_interface.launch launch file for the test
17 from robocluedo_msgs.srv
import CheckSolution, CheckSolutionRequest, CheckSolutionResponse
18 from std_msgs.msg
import Empty
19 from robocluedo_msgs.msg
import Hint
20 from robocluedo_msgs.srv
import AddHint, AddHintRequest, AddHintResponse
21 from robocluedo_msgs.srv
import FindConsistentHypotheses, FindConsistentHypothesesRequest, FindConsistentHypothesesResponse
22 from robocluedo_msgs.msg
import Hypothesis
23 from robocluedo_msgs.srv
import DiscardHypothesis, DiscardHypothesisRequest, DiscardHypothesisResponse
24 from std_srvs.srv
import Trigger, TriggerRequest, TriggerResponse
29 client_name_check_solution =
"/check_solution"
30 client_check_solution =
None
32 publisher_name_hint_sig =
"/hint_signal"
33 publisher_hint_sig =
None
35 subscriber_name_hint =
"/hint"
37 client_name_add_hint =
"/cluedo_armor/add_hint"
38 client_add_hint =
None
40 client_name_find_consistent_h =
"/cluedo_armor/find_consistent_h"
41 client_find_consistent_h =
None
43 client_name_wrong_h =
"/cluedo_armor/wrong_hypothesis"
46 client_name_backup =
"/cluedo_armor/backup"
52 test_name =
"test_oracle_plus_interface"
56 srv_hint = AddHintRequest( )
59 # the numeric ID of the hint
62 # fields of the property
69 srv_hint.property = prop
70 srv_hint.Aelem =
"HP" + str( id )
79 global client_add_hint
81 rospy.loginfo(
"[%s] (number %d) received: HP%d(%s:%s)", test_name, hint_idx, hint.HintID, hint.HintType, hint.HintContent )
83 rospy.loginfo(
"[%s] adding hint to the ontology... ", test_name )
88 rospy.loginfo(
"[%s] consistent hypotheses right now: ", test_name )
89 rospy.loginfo(
"[%s] received size : %d ", test_name, len(hplist) )
90 for i
in range( len(hplist) ):
91 rospy.loginfo(
"[%s] -> %s(where:%s, what:%s, who:%s)", test_name, hplist[i].tag, hplist[i].where, hplist[i].what, hplist[i].who )
99 global publisher_name_hint_sig
100 global client_check_solution
105 for hintno
in range( 50 ):
106 rospy.loginfo(
"[%s] sending signal %d ...", test_name, hint_idx )
107 publisher_hint_sig.publish( Empty( ) )
108 hint_idx = hint_idx + 1
109 rospy.sleep( rospy.Duration( 0.1 ) )
111 rospy.loginfo(
"[%s] saving the ontology...", test_name )
128 rospy.loginfo(
"[%s] closing...", test_name )
133 if __name__ ==
"__main__":
134 rospy.init_node( test_name )
135 rospy.on_shutdown( on_shut_msg )
138 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_check_solution )
139 rospy.wait_for_service( client_name_check_solution )
140 client_check_solution = rospy.ServiceProxy( client_name_check_solution, CheckSolution )
141 rospy.loginfo(
"[%s] OK!", test_name )
144 rospy.loginfo(
"[%s] opening publisher to topic [%s] ...", test_name, publisher_name_hint_sig )
145 publisher_hint_sig = rospy.Publisher( publisher_name_hint_sig, Empty, queue_size=1 )
146 rospy.loginfo(
"[%s] OK!", test_name )
149 rospy.loginfo(
"[%s] subscribing to topic [%s] ...", test_name, subscriber_name_hint )
151 rospy.Subscriber( subscriber_name_hint, Hint, callback_hint )
152 rospy.loginfo(
"[%s] OK!", test_name )
155 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_add_hint )
156 rospy.wait_for_service( client_name_add_hint )
157 client_add_hint = rospy.ServiceProxy( client_name_add_hint, AddHint )
158 rospy.loginfo(
"[%s] OK!", test_name )
161 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_find_consistent_h )
162 rospy.wait_for_service( client_name_find_consistent_h )
163 client_find_consistent_h = rospy.ServiceProxy( client_name_find_consistent_h, FindConsistentHypotheses )
164 rospy.loginfo(
"[%s] OK!", test_name )
167 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_wrong_h )
168 rospy.wait_for_service( client_name_wrong_h )
169 client_wrong_h = rospy.ServiceProxy( client_name_wrong_h, DiscardHypothesis )
170 rospy.loginfo(
"[%s] OK!", test_name )
173 rospy.loginfo(
"[%s] asking for service [%s] ...", test_name, client_name_backup )
174 rospy.wait_for_service( client_name_backup )
175 client_backup = rospy.ServiceProxy( client_name_backup, Trigger )
176 rospy.loginfo(
"[%s] OK!", test_name )