Apollo 10.0
自动驾驶开放平台
control_tester.cc 文件参考
#include "gflags/gflags.h"
#include "modules/common_msgs/chassis_msgs/chassis.pb.h"
#include "modules/common_msgs/control_msgs/pad_msg.pb.h"
#include "modules/common_msgs/localization_msgs/localization.pb.h"
#include "modules/common_msgs/planning_msgs/planning.pb.h"
#include "cyber/common/file.h"
#include "cyber/common/log.h"
#include "cyber/cyber.h"
#include "cyber/init.h"
#include "cyber/time/rate.h"
#include "cyber/time/time.h"
#include "modules/common/adapters/adapter_gflags.h"
#include "modules/control/control_component/common/control_gflags.h"
control_tester.cc 的引用(Include)关系图:

浏览源代码.

函数

 DEFINE_string (chassis_test_file, "modules/control/testdata/control_tester/chassis.pb.txt", "Used for sending simulated Chassis content to the control node.")
 
 DEFINE_string (localization_test_file, "modules/control/testdata/control_tester/localization.pb.txt", "Used for sending simulated localization to the control node.")
 
 DEFINE_string (pad_msg_test_file, "modules/control/testdata/control_tester/pad_msg.pb.txt", "Used for sending simulated PadMsg content to the control node.")
 
 DEFINE_string (planning_test_file, "modules/control/testdata/control_tester/planning.pb.txt", "Used for sending simulated Planning content to the control node.")
 
 DEFINE_int32 (num_seconds, 10, "Length of execution.")
 
 DEFINE_int32 (feed_frequency, 10, "Frequency with which protos are fed to control.")
 
int main (int argc, char **argv)
 

函数说明

◆ DEFINE_int32() [1/2]

DEFINE_int32 ( feed_frequency  ,
10  ,
"Frequency with which protos are fed to control."   
)

◆ DEFINE_int32() [2/2]

DEFINE_int32 ( num_seconds  ,
10  ,
"Length of execution."   
)

◆ DEFINE_string() [1/4]

DEFINE_string ( chassis_test_file  ,
"modules/control/testdata/control_tester/chassis.pb.txt"  ,
"Used for sending simulated Chassis content to the control node."   
)

◆ DEFINE_string() [2/4]

DEFINE_string ( localization_test_file  ,
"modules/control/testdata/control_tester/localization.pb.txt"  ,
"Used for sending simulated localization to the control node."   
)

◆ DEFINE_string() [3/4]

DEFINE_string ( pad_msg_test_file  ,
"modules/control/testdata/control_tester/pad_msg.pb.txt"  ,
"Used for sending simulated PadMsg content to the control node."   
)

◆ DEFINE_string() [4/4]

DEFINE_string ( planning_test_file  ,
"modules/control/testdata/control_tester/planning.pb.txt"  ,
"Used for sending simulated Planning content to the control node."   
)

◆ main()

int main ( int  argc,
char **  argv 
)

在文件 control_tester.cc52 行定义.

52 {
59 using std::this_thread::sleep_for;
60
61 google::ParseCommandLineFlags(&argc, &argv, true);
62 apollo::cyber::Init(argv[0]);
63 FLAGS_alsologtostderr = true;
64
65 Chassis chassis;
66 if (!GetProtoFromFile(FLAGS_chassis_test_file, &chassis)) {
67 AERROR << "failed to load file: " << FLAGS_chassis_test_file;
68 return -1;
69 }
70
71 LocalizationEstimate localization;
72 if (!GetProtoFromFile(FLAGS_localization_test_file, &localization)) {
73 AERROR << "failed to load file: " << FLAGS_localization_test_file;
74 return -1;
75 }
76
77 PadMessage pad_msg;
78 if (!GetProtoFromFile(FLAGS_pad_msg_test_file, &pad_msg)) {
79 AERROR << "failed to load file: " << FLAGS_pad_msg_test_file;
80 return -1;
81 }
82
83 ADCTrajectory trajectory;
84 if (!GetProtoFromFile(FLAGS_planning_test_file, &trajectory)) {
85 AERROR << "failed to load file: " << FLAGS_planning_test_file;
86 return -1;
87 }
88
89 std::shared_ptr<apollo::cyber::Node> node(
90 apollo::cyber::CreateNode("control_tester"));
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.
Definition time.h:31
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
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,...
Definition file.cc:132
bool Init(const char *binary_name, const std::string &dag_info)
Definition init.cc:98
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space)
Definition cyber.cc:33