提交 538c08d1 编写于 作者: D Dong Li 提交者: siyangy

added PointCloudAdapter specialization (#122)

Previous implementation could not correctly distinguish ros message and
protobuf message
上级 b8c4562b
......@@ -46,6 +46,7 @@ cc_library(
"//modules/common/time",
"//modules/common/util",
"@com_github_google_protobuf//:protobuf",
"@ros//:ros_common",
"@glog//:glog",
],
)
......@@ -63,6 +64,7 @@ cc_test(
":adapter",
":adapter_gflags",
"//modules/localization/proto:localization_proto",
"@ros//:ros_common",
"@gtest//:main",
],
)
......@@ -82,10 +84,10 @@ cc_library(
"//modules/localization/proto:gps_proto",
"//modules/localization/proto:imu_proto",
"//modules/localization/proto:localization_proto",
"//modules/map/proto:map_proto",
"//modules/perception/proto:perception_proto",
"//modules/planning/proto:planning_proto",
"//modules/prediction/proto:prediction_proto",
"//modules/map/proto:map_proto",
"@glog//:glog",
],
)
......
......@@ -28,6 +28,8 @@
#include <string>
#include <type_traits>
#include <sensor_msgs/PointCloud2.h>
#include "glog/logging.h"
#include "google/protobuf/descriptor.h"
#include "google/protobuf/message.h"
......@@ -120,25 +122,9 @@ class Adapter {
* @param message_file the path to the file that contains a (usually
* proto) message of DataType.
*/
template <class U = D>
void FeedFile(
const std::string &message_file,
typename std::enable_if<
std::is_base_of<::google::protobuf::Message, U>::value>::type * = 0) {
D data;
CHECK(apollo::common::util::GetProtoFromFile(message_file, &data))
<< "Unable to parse input pb file " << message_file;
FeedProto(data);
}
/**
* @brief reads the ros message from the file, and push it into
* the adapter's data queue.
* @param message_file the path to the file that contains a (usually
* proto) message of DataType.
*/
void FeedFile(const std::string &message_file) {
// FIXME: specific processing logic for ros Message
template <class T = D>
bool FeedFile(const std::string &message_file) {
return FeedFile(message_file, IdentifierType<T>());
}
/**
......@@ -249,6 +235,24 @@ class Adapter {
uint32_t GetSeqNum() const { return seq_num_; }
private:
template <typename T>
struct IdentifierType {};
template <class T>
bool FeedFile(const std::string &message_file, IdentifierType<T>) {
D data;
if (!apollo::common::util::GetProtoFromFile(message_file, &data)) {
AERROR << "Unable to parse input pb file " << message_file;
return false;
}
FeedProto(data);
return true;
}
bool FeedFile(const std::string &message_file,
IdentifierType<::sensor_msgs::PointCloud2>) {
return false;
}
// HasSequenceNumber returns false for non-proto-message data types.
template <typename InputMessageType>
static bool HasSequenceNumber(
......
......@@ -61,10 +61,12 @@ namespace adapter {
static name##Adapter *Get##name() { \
return instance()->InternalGet##name(); \
} \
static void Feed##name##ProtoFile(const std::string &proto_file) { \
CHECK(instance()->name##_) \
<< "Initialize adapter before feeding protobuf"; \
Get##name()->FeedFile(proto_file); \
static bool Feed##name##File(const std::string &proto_file) { \
if (!instance()->name##_) { \
AERROR << "Initialize adapter before feeding protobuf"; \
return false; \
} \
return Get##name()->FeedFile(proto_file); \
} \
static void Publish##name(const name##Adapter::DataType &data) { \
instance()->InternalPublish##name(data); \
......
......@@ -43,7 +43,6 @@ Status ControllerAgent::InitializeConf(const ControlConf *control_conf) {
return Status(ErrorCode::CONTROL_INIT_ERROR, "Failed to load config");
}
control_conf_ = control_conf;
AINFO << control_conf_->DebugString();
for (auto controller_type : control_conf_->active_controllers()) {
auto controller = controller_factory_.CreateObject(
static_cast<ControlConf::ControllerType>(controller_type));
......
......@@ -67,21 +67,36 @@ bool ControlTestBase::test_control() {
AdapterManager::Init(FLAGS_adapter_config_path);
if (!FLAGS_test_pad_file.empty()) {
PadMessage pad_message;
apollo::common::util::GetProtoFromFile(
FLAGS_test_data_dir + FLAGS_test_pad_file, &pad_message);
if (!apollo::common::util::GetProtoFromFile(
FLAGS_test_data_dir + FLAGS_test_pad_file, &pad_message)) {
AERROR << "Failed to load PadMesssage from file " << FLAGS_test_data_dir
<< FLAGS_test_pad_file;
return false;
}
control_.OnPad(pad_message);
}
if (!FLAGS_test_localization_file.empty()) {
AdapterManager::FeedLocalizationProtoFile(FLAGS_test_data_dir +
FLAGS_test_localization_file);
if (!AdapterManager::FeedLocalizationFile(FLAGS_test_data_dir +
FLAGS_test_localization_file)) {
AERROR << "Failed to load localization file " << FLAGS_test_data_dir
<< FLAGS_test_localization_file;
return false;
}
}
if (!FLAGS_test_planning_file.empty()) {
AdapterManager::FeedPlanningProtoFile(FLAGS_test_data_dir +
FLAGS_test_planning_file);
if (!AdapterManager::FeedPlanningFile(FLAGS_test_data_dir +
FLAGS_test_planning_file)) {
AERROR << "Failed to load planning file " << FLAGS_test_data_dir
<< FLAGS_test_planning_file;
return false;
}
}
if (!FLAGS_test_chassis_file.empty()) {
AdapterManager::FeedChassisProtoFile(FLAGS_test_data_dir +
FLAGS_test_chassis_file);
if (!AdapterManager::FeedChassisFile(FLAGS_test_data_dir +
FLAGS_test_chassis_file)) {
AERROR << "Failed to load chassis file " << FLAGS_test_data_dir
<< FLAGS_test_chassis_file;
}
}
if (!FLAGS_test_monitor_file.empty()) {
MonitorMessage monitor_message;
......
......@@ -64,10 +64,10 @@ int main(int argc, char **argv) {
AdapterManager::Init();
AINFO << "AdapterManager is initialized.";
for (int i = 0; i < FLAGS_num_seconds * FLAGS_feed_frequency; ++i) {
AdapterManager::FeedChassisProtoFile(FLAGS_chassis_test_file);
AdapterManager::FeedLocalizationProtoFile(FLAGS_l10n_test_file);
AdapterManager::FeedPadProtoFile(FLAGS_pad_msg_test_file);
AdapterManager::FeedPlanningProtoFile(FLAGS_planning_test_file);
AdapterManager::FeedChassisFile(FLAGS_chassis_test_file);
AdapterManager::FeedLocalizationFile(FLAGS_l10n_test_file);
AdapterManager::FeedPadFile(FLAGS_pad_msg_test_file);
AdapterManager::FeedPlanningFile(FLAGS_planning_test_file);
sleep_for(std::chrono::milliseconds(1000 / FLAGS_feed_frequency));
}
AINFO << "Successfully fed proto files.";
......
......@@ -73,10 +73,8 @@ message ADCTrajectory {
optional apollo.common.Header header = 1;
optional double total_path_length = 2; // in meters
optional double total_path_time = 3; // in seconds
repeated ADCTrajectoryPoint adc_trajectory_point = 4 [deprecated=true];
repeated apollo.common.TrajectoryPoint trajectory_point = 12;
optional EStop estop = 6;
repeated ADCPathPoint adc_path_point = 7 [deprecated=true];
repeated apollo.common.PathPoint path_point = 13;
optional apollo.planning_internal.Debug debug = 8;
// is_replan == true mean replan triggered
......@@ -85,4 +83,7 @@ message ADCTrajectory {
optional apollo.canbus.Chassis.GearPosition gear = 10;
optional apollo.common.VehicleSignal signal = 11;
optional apollo.planning.DecisionResult decision = 14;
repeated ADCPathPoint adc_path_point = 7 [deprecated=true];
repeated ADCTrajectoryPoint adc_trajectory_point = 4 [deprecated=true];
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册