52 {
59 using std::this_thread::sleep_for;
60
61 google::ParseCommandLineFlags(&argc, &argv, true);
63 FLAGS_alsologtostderr = true;
64
65 Chassis chassis;
67 AERROR <<
"failed to load file: " << FLAGS_chassis_test_file;
68 return -1;
69 }
70
71 LocalizationEstimate localization;
73 AERROR <<
"failed to load file: " << FLAGS_localization_test_file;
74 return -1;
75 }
76
77 PadMessage pad_msg;
79 AERROR <<
"failed to load file: " << FLAGS_pad_msg_test_file;
80 return -1;
81 }
82
83 ADCTrajectory trajectory;
85 AERROR <<
"failed to load file: " << FLAGS_planning_test_file;
86 return -1;
87 }
88
89 std::shared_ptr<apollo::cyber::Node> node(
91 auto chassis_writer = node->CreateWriter<Chassis>(FLAGS_chassis_topic);
92 auto localization_writer =
93 node->CreateWriter<LocalizationEstimate>(FLAGS_localization_topic);
94 auto pad_msg_writer = node->CreateWriter<PadMessage>(FLAGS_pad_topic);
95 auto planning_writer =
96 node->CreateWriter<ADCTrajectory>(FLAGS_planning_trajectory_topic);
97
98 for (int i = 0; i < FLAGS_num_seconds * FLAGS_feed_frequency; ++i) {
99 chassis_writer->Write(chassis);
100 localization_writer->Write(localization);
101 pad_msg_writer->Write(pad_msg);
102 planning_writer->Write(trajectory);
103 sleep_for(std::chrono::milliseconds(1000 / FLAGS_feed_frequency));
104 }
105 AINFO <<
"Successfully fed proto files.";
106 return 0;
107}
Cyber has builtin time type Time.
bool GetProtoFromFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as a representation of protobufs,...
bool Init(const char *binary_name, const std::string &dag_info)
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space)