forked from zivid/zivid-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsample_capture_assistant.py
executable file
·54 lines (40 loc) · 1.71 KB
/
sample_capture_assistant.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
#!/usr/bin/env python
import rospy
import rosnode
from zivid_camera.srv import *
from std_msgs.msg import String
from sensor_msgs.msg import PointCloud2, Image
class Sample:
def __init__(self):
rospy.init_node("sample_capture_assistant_py", anonymous=True)
rospy.loginfo("Starting sample_capture_assistant.py")
ca_suggest_settings_service = "/zivid_camera/capture_assistant/suggest_settings"
rospy.wait_for_service(ca_suggest_settings_service, 30.0)
self.capture_assistant_service = rospy.ServiceProxy(
ca_suggest_settings_service, CaptureAssistantSuggestSettings
)
self.capture_service = rospy.ServiceProxy("/zivid_camera/capture", Capture)
rospy.Subscriber("/zivid_camera/points/xyzrgba", PointCloud2, self.on_points)
rospy.Subscriber("/zivid_camera/color/image_color", Image, self.on_image_color)
def capture_assistant_suggest_settings(self):
max_capture_time = rospy.Duration.from_sec(1.20)
rospy.loginfo(
"Calling capture assistant service with max capture time = %.2f sec",
max_capture_time.to_sec(),
)
self.capture_assistant_service(
max_capture_time=max_capture_time,
ambient_light_frequency=CaptureAssistantSuggestSettingsRequest.AMBIENT_LIGHT_FREQUENCY_NONE,
)
def capture(self):
rospy.loginfo("Calling capture service")
self.capture_service()
def on_points(self, data):
rospy.loginfo("PointCloud received")
def on_image_color(self, data):
rospy.loginfo("2D color image received")
if __name__ == "__main__":
s = Sample()
s.capture_assistant_suggest_settings()
s.capture()
rospy.spin()