6 from std_msgs.msg
import String
7 from sensor_msgs.msg
import PointCloud2, Image
12 rospy.init_node(
"sample_capture_assistant_py", anonymous=
True)
14 rospy.loginfo(
"Starting sample_capture_assistant.py")
16 ca_suggest_settings_service =
"/zivid_camera/capture_assistant/suggest_settings" 18 rospy.wait_for_service(ca_suggest_settings_service, 30.0)
21 ca_suggest_settings_service, CaptureAssistantSuggestSettings
25 rospy.Subscriber(
"/zivid_camera/points/xyzrgba", PointCloud2, self.
on_points)
26 rospy.Subscriber(
"/zivid_camera/color/image_color", Image, self.
on_image_color)
29 max_capture_time = rospy.Duration.from_sec(1.20)
31 "Calling capture assistant service with max capture time = %.2f sec",
32 max_capture_time.to_sec(),
35 max_capture_time=max_capture_time,
36 ambient_light_frequency=CaptureAssistantSuggestSettingsRequest.AMBIENT_LIGHT_FREQUENCY_NONE,
40 rospy.loginfo(
"Calling capture service")
44 rospy.loginfo(
"PointCloud received")
47 rospy.loginfo(
"2D color image received")
50 if __name__ ==
"__main__":
52 s.capture_assistant_suggest_settings()
def on_image_color(self, data)
def on_points(self, data)
capture_assistant_service
def capture_assistant_suggest_settings(self)