5 import dynamic_reconfigure.client
7 from std_msgs.msg
import String
8 from sensor_msgs.msg
import Image
13 rospy.init_node(
"sample_capture_2d_py", anonymous=
True)
15 rospy.loginfo(
"Starting sample_capture_2d.py")
17 rospy.wait_for_service(
"/zivid_camera/capture_2d", 30.0)
19 rospy.Subscriber(
"/zivid_camera/color/image_color", Image, self.
on_image_color)
22 "/zivid_camera/capture_2d", Capture2D
25 rospy.loginfo(
"Configuring 2D settings")
26 acquisition_0_client = dynamic_reconfigure.client.Client(
27 "/zivid_camera/settings_2d/acquisition_0" 29 acquisition_0_config = {
32 "exposure_time": 10000,
35 acquisition_0_client.update_configuration(acquisition_0_config)
38 rospy.loginfo(
"Calling capture service")
42 rospy.loginfo(
"Color image received")
46 if __name__ ==
"__main__":
def on_image_color(self, data)