sample_capture_assistant.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import rosnode
5 from zivid_camera.srv import *
6 from std_msgs.msg import String
7 from sensor_msgs.msg import PointCloud2, Image
8 
9 
10 class Sample:
11  def __init__(self):
12  rospy.init_node("sample_capture_assistant_py", anonymous=True)
13 
14  rospy.loginfo("Starting sample_capture_assistant.py")
15 
16  ca_suggest_settings_service = "/zivid_camera/capture_assistant/suggest_settings"
17 
18  rospy.wait_for_service(ca_suggest_settings_service, 30.0)
19 
20  self.capture_assistant_service = rospy.ServiceProxy(
21  ca_suggest_settings_service, CaptureAssistantSuggestSettings
22  )
23  self.capture_service = rospy.ServiceProxy("/zivid_camera/capture", Capture)
24 
25  rospy.Subscriber("/zivid_camera/points/xyzrgba", PointCloud2, self.on_points)
26  rospy.Subscriber("/zivid_camera/color/image_color", Image, self.on_image_color)
27 
29  max_capture_time = rospy.Duration.from_sec(1.20)
30  rospy.loginfo(
31  "Calling capture assistant service with max capture time = %.2f sec",
32  max_capture_time.to_sec(),
33  )
35  max_capture_time=max_capture_time,
36  ambient_light_frequency=CaptureAssistantSuggestSettingsRequest.AMBIENT_LIGHT_FREQUENCY_NONE,
37  )
38 
39  def capture(self):
40  rospy.loginfo("Calling capture service")
41  self.capture_service()
42 
43  def on_points(self, data):
44  rospy.loginfo("PointCloud received")
45 
46  def on_image_color(self, data):
47  rospy.loginfo("2D color image received")
48 
49 
50 if __name__ == "__main__":
51  s = Sample()
52  s.capture_assistant_suggest_settings()
53  s.capture()
54  rospy.spin()


zivid_samples
Author(s):
autogenerated on Sat Apr 17 2021 02:51:09