-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathattach_client.py
79 lines (61 loc) · 2.27 KB
/
attach_client.py
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
from gazebo_msgs.srv import SetEntityState
from std_msgs.msg import String
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from rclpy.callback_groups import ReentrantCallbackGroup
import time
class ClientAsync(Node):
def __init__(self):
super().__init__('service_client')
self.reentrant_group_1 = ReentrantCallbackGroup()
self.client = self.create_client(SetEntityState , '/demo/set_entity_state')
self.timer = self.create_timer(0.5, self.timer_callback, callback_group=self.reentrant_group_1)
self.subscriber_up = self.create_subscription(
String,
'/elevator_up',
self.up_callback,
10,
callback_group=self.reentrant_group_1)
self.subscriber_down = self.create_subscription(
String,
'/elevator_down',
self.down_callback,
10,
callback_group=self.reentrant_group_1)
while not self.client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = SetEntityState.Request()
self.req.state.name = "rb2_simple_cart"
self.req.state.reference_frame = "rb1_robot"
self.req.state.pose.position.z = 0.1
self.attach = 0
def up_callback(self, msg):
self.attach = 1
def down_callback(self, msg):
self.attach = 2
def timer_callback(self):
if self.attach is 1:
self.future = self.client.call_async(self.req)
elif self.attach is 2:
self.req = SetEntityState.Request()
self.req.state.name = "rb2_simple_cart"
self.req.state.reference_frame = "rb2_simple_cart"
self.req.state.pose.position.z = 0.0
self.attach = 0
time.sleep(2)
self.future = self.client.call_async(self.req)
else:
pass
def main(args=None):
rclpy.init(args=args)
client = ClientAsync()
executor = MultiThreadedExecutor(num_threads=4)
executor.add_node(client)
try:
executor.spin()
finally:
client.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()