def load_parameters (num_cameras): """ Initialize global variables. """ global camera_types, demo_type_dir, master_file, demo_num, demo_info,\ latest_demo_file, cam_stop_request, cam_publish_request, topic_writer demo_type_dir = osp.join(demo_files_dir, demo_type) if not osp.isdir(demo_type_dir): os.mkdir(demo_type_dir) # Taken care of outside. master_file = osp.join(demo_type_dir, master_name) if not osp.isfile(master_file): with open(master_file, "w") as f: f.write("name: %s\n"%demo_type) f.write("h5path: %s\n"%(demo_type+".h5")) f.write("demos: \n") camera_types = {(i+1):None for i in range(num_cameras)} for cam in camera_types: with open(osp.join(hd_data_dir,'camera_types','camera%i'%cam),'r') as fh: camera_types[cam] = fh.read() save_image_services[cam] = rospy.ServiceProxy("saveImagescamera%i"%cam, SaveImage) cam_save_requests[cam] = SaveImageRequest() cam_save_requests[cam].start = True cam_save_requests[cam].publish = False if camera_types[cam] == "rgb": with open(osp.join(hd_data_dir,'camera_types','camera%i_model'%cam),'r') as fh: camera_models[cam] = fh.read() cam_stop_request = SaveImageRequest() cam_stop_request.start = False cam_stop_request.publish = False cam_publish_request = SaveImageRequest() cam_publish_request.start = False cam_publish_request.publish = True # Get number of latest demo recorded latest_demo_file = osp.join(demo_type_dir, latest_demo_name) if osp.isfile(latest_demo_file): try: with open(latest_demo_file,'r') as fh: demo_num = int(fh.read()) + 1 except: demo_num = 1 else: demo_num = 1 topics = ['/l_pot_angle', '/r_pot_angle','/segment','/tf'] topic_types = [Float32, Float32, Segment, tfMessage] topic_writer = TopicWriter(topics=topics, topic_types=topic_types) yellowprint("Started listening to the different topics.")
import rospy import time import roslib roslib.load_manifest('record_rgbd_service') from record_rgbd_service.srv import SaveImage, SaveImageRequest, SaveImageResponse rospy.init_node("test_image_save_service") save_service = rospy.ServiceProxy("saveImagescamera1", SaveImage) req = SaveImageRequest () req.start = True req.folder_name = "/home/sibi/temp/check_service" save_service(req) time.sleep(2) req.start = False save_service(req)