def main(argv): """ Main node """ node = cyber.Node("rtk_recorder") argv = FLAGS(argv) log_dir = os.path.dirname( os.path.abspath(__file__)) + "/../../../data/log/" if not os.path.exists(log_dir): os.makedirs(log_dir) Logger.config(log_file=log_dir + "rtk_recorder.log", use_stdout=True, log_level=logging.DEBUG) print("runtime log is in %s%s" % (log_dir, "rtk_recorder.log")) record_file = log_dir + "/garage.csv" recorder = RtkRecord(record_file) atexit.register(recorder.shutdown) node.create_reader('/apollo/canbus/chassis', chassis_pb2.Chassis, recorder.chassis_callback) node.create_reader('/apollo/localization/pose', localization_pb2.LocalizationEstimate, recorder.localization_callback) while not cyber.is_shutdown(): time.sleep(0.002)
def main(): """ Main cyber """ parser = argparse.ArgumentParser( description='Generate Planning Trajectory from Data File') parser.add_argument( '-s', '--speedmulti', help='Speed multiplier in percentage (Default is 100) ', type=float, default='100') parser.add_argument('-c', '--complete', help='Generate complete path (t/F)', default='F') parser.add_argument('-r', '--replan', help='Always replan based on current position(t/F)', default='F') args = vars(parser.parse_args()) node = cyber.Node("rtk_player") Logger.config(log_file=os.path.join(APOLLO_ROOT, 'data/log/rtk_player.log'), use_stdout=True, log_level=logging.DEBUG) record_file = os.path.join(APOLLO_ROOT, 'data/log/garage.csv') player = RtkPlayer(record_file, node, args['speedmulti'], args['complete'].lower(), args['replan'].lower()) atexit.register(player.shutdown) node.create_reader('/apollo/canbus/chassis', chassis_pb2.Chassis, player.chassis_callback) node.create_reader('/apollo/localization/pose', localization_pb2.LocalizationEstimate, player.localization_callback) node.create_reader('/apollo/control/pad', pad_msg_pb2.PadMessage, player.padmsg_callback) while not cyber.is_shutdown(): now = cyber_time.Time.now().to_sec() player.publish_planningmsg() sleep_time = 0.1 - (cyber_time.Time.now().to_sec() - now) if sleep_time > 0: time.sleep(sleep_time)
def main(argv): """ Main rosnode """ rospy.init_node('lane_recorder', anonymous=True) parser = argparse.ArgumentParser( description='Record Localization and Mobileye Lane Detection in CSV Format') parser.add_argument( '-d', '--dir', help='Output and log directory', type=str, default='/tmp/') parser.add_argument( '-o', '--output_file', help='Output CSV file name', type=str, default='lane.csv') args = vars(parser.parse_args()) log_dir = args['dir'] record_file = log_dir + "/" + args['output_file'] if not os.path.exists(log_dir): os.makedirs(log_dir) Logger.config( log_file=log_dir + "lane_recorder.log", use_stdout=True, log_level=logging.DEBUG) print("runtime log is in %s%s" % (log_dir, "lane_recorder.log")) recorder = LaneRecord(record_file) atexit.register(recorder.shutdown) rospy.Subscriber('/apollo/sensor/mobileye', mobileye_pb2.Mobileye, recorder.mobileye_callback) rospy.Subscriber('/apollo/localization/pose', localization_pb2.LocalizationEstimate, recorder.localization_callback) rospy.spin()