-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathknowrob_designator_client.py
More file actions
executable file
·164 lines (144 loc) · 4.94 KB
/
knowrob_designator_client.py
File metadata and controls
executable file
·164 lines (144 loc) · 4.94 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
# Topic-based client for all KnowRob designator messages
import rospy
import uuid
from time import sleep
from std_msgs.msg import Header
from knowrob_designator.msg import (
PushObjectDesignator,
DesignatorInit,
DesignatorResolutionStart,
DesignatorResolutionFinished,
DesignatorExecutionStart,
DesignatorExecutionFinished
)
from knowrob_ros.knowrob_ros_lib import KnowRobRosLib
from knowrob_ros.knowrob_ros_lib import get_default_modalframe
def testQueryDesig():
know = KnowRobRosLib()
know.init_clients() # After rospy.init_node()
query = "triple(?d, rdf:type, soma:PyCramDesignator)"
rospy.loginfo(f"asking [{query}] ...")
result = know.ask_one(query, get_default_modalframe())
rospy.loginfo(f"response: [{result}]")
def main():
rospy.init_node('knowrob_designator_topic_client')
now = rospy.Time.now()
# Publishers
push_pub = rospy.Publisher('/knowrob/designator/push_object_designator', PushObjectDesignator, queue_size=10)
init_pub = rospy.Publisher('/knowrob/designator/init', DesignatorInit, queue_size=10)
resolve_start_pub = rospy.Publisher('/knowrob/designator/resolving_started', DesignatorResolutionStart, queue_size=10)
resolve_finished_pub = rospy.Publisher('/knowrob/designator/resolving_finished', DesignatorResolutionFinished, queue_size=10)
exec_start_pub = rospy.Publisher('/knowrob/designator/execution_start', DesignatorExecutionStart, queue_size=10)
exec_finished_pub = rospy.Publisher('/knowrob/designator/execution_finished', DesignatorExecutionFinished, queue_size=10)
rospy.sleep(1.0) # Wait for publishers to register
##########################################################
############### Object Designator ########################
push_msg = PushObjectDesignator()
push_msg.stamp = now
push_msg.json_designator = """
{
"anObject": {
"name": "Milk1",
"type": "Milk",
"pose": {
"px": 1.0,
"py": 1.0,
"pz": 0.0,
"rx": 0.0,
"ry": 0.0,
"rz": 0.0,
"rw": 1.0,
"frame": "map"
}
}
}
"""
rospy.loginfo("Publishing PushObjectDesignator...")
push_pub.publish(push_msg)
##########################################################
############### Action Designators ########################
json_designator = """
{
"anAction": {
"type": "Transporting",
"object_designator": {
"anObject": {
"type": "Milk"
}
},
"target": {
"theLocation": {
"goal": {
"theObject": {
"name": "Table1"
}
}
}
}
}
}
"""
resolved_designator = """
{
"anAction": {
"type": "Transporting",
"object_designator": {
"anObject": {
"type": "Milk"
}
},
"target_location": {
'px': 2.1,
'py': 2.35,
'pz': 0.8,
'rx': 0.0,
'ry': 0.0,
'rz': 0.0,
'rw': 1.0,
'frame': 'map'
}
}
}
}
"""
designator_id = f"desig_{uuid.uuid4()}"
resolved_id = f"desig_{uuid.uuid4()}"
init_msg = DesignatorInit()
init_msg.stamp = now
init_msg.designator_id = designator_id
init_msg.parent_id = ""
init_msg.json_designator = json_designator
rospy.loginfo("Publishing DesignatorInit...")
init_pub.publish(init_msg)
resolve_start_msg = DesignatorResolutionStart()
resolve_start_msg.stamp = now
resolve_start_msg.designator_id = designator_id
resolve_start_msg.json_designator = json_designator
rospy.loginfo("Publishing DesignatorResolutionStart...")
resolve_start_pub.publish(resolve_start_msg)
rospy.sleep(1.0)
resolve_finished_msg = DesignatorResolutionFinished()
resolve_finished_msg.stamp = rospy.Time.now()
resolve_finished_msg.designator_id = resolved_id
resolve_finished_msg.resolved_from_id = designator_id
resolve_finished_msg.json_designator = resolved_designator
rospy.loginfo("Publishing DesignatorResolutionFinished...")
resolve_finished_pub.publish(resolve_finished_msg)
exec_start_msg = DesignatorExecutionStart()
exec_start_msg.stamp = now
exec_start_msg.designator_id = resolved_id
exec_start_msg.json_designator = resolved_designator
rospy.loginfo("Publishing DesignatorExecutionStart...")
exec_start_pub.publish(exec_start_msg)
exec_finished_msg = DesignatorExecutionFinished()
exec_finished_msg.stamp = now
exec_finished_msg.designator_id = resolved_id
exec_finished_msg.json_designator = resolved_designator
rospy.loginfo("Publishing DesignatorExecutionFinished...")
exec_finished_pub.publish(exec_finished_msg)
# Finally do some testing queries with KnowRob
testQueryDesig()
if __name__ == '__main__':
main()