提交 3bd0ba6f 编写于 作者: S siyangy 提交者: Jiangtao Hu

simplify FillHeader

上级 1e1e1aa7
......@@ -141,7 +141,7 @@ Status Canbus::Start() {
void Canbus::PublishChassis() {
Chassis chassis = vehicle_controller_->chassis();
AdapterManager::FillChassisHeader(FLAGS_node_name, chassis.mutable_header());
AdapterManager::FillChassisHeader(FLAGS_node_name, &chassis);
AdapterManager::PublishChassis(chassis);
ADEBUG << chassis.ShortDebugString();
......
......@@ -307,8 +307,7 @@ class Teleop {
}
void Send() {
AdapterManager::FillControlCommandHeader("control",
control_command_.mutable_header());
AdapterManager::FillControlCommandHeader("control", &control_command_);
AdapterManager::PublishControlCommand(control_command_);
ADEBUG << "Control Command send OK:" << control_command_.ShortDebugString();
}
......
......@@ -114,7 +114,9 @@ class Adapter {
/**
* @brief returns the topic name that this adapter listens to.
*/
const std::string& topic_name() const { return topic_name_; }
const std::string& topic_name() const {
return topic_name_;
}
/**
* @brief reads the proto message from the file, and push it into
......@@ -132,7 +134,9 @@ class Adapter {
* the adapter.
* @param data the input data.
*/
void FeedData(const D& data) { EnqueueData(data); }
void FeedData(const D& data) {
EnqueueData(data);
}
/**
* @brief the callback that will be invoked whenever a new
......@@ -205,14 +209,18 @@ class Adapter {
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator begin() const { return observed_queue_.begin(); }
Iterator begin() const {
return observed_queue_.begin();
}
/**
* @brief returns an iterator representing the tail of the observing
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator end() const { return observed_queue_.end(); }
Iterator end() const {
return observed_queue_.end();
}
/**
* @brief registers the provided callback function to the adapter,
......@@ -220,14 +228,18 @@ class Adapter {
* message hits the adapter.
* @param callback the callback with signature void(const D &).
*/
void SetCallback(Callback callback) { receive_callback_ = callback; }
void SetCallback(Callback callback) {
receive_callback_ = callback;
}
/**
* @brief fills the fields module_name, timestamp_sec and
* sequence_num in the header.
*/
void FillHeader(const std::string& module_name,
apollo::common::Header* header) {
void FillHeader(const std::string& module_name, D* data) {
static_assert(std::is_base_of<google::protobuf::Message, D>::value,
"Can only fill header to proto messages!");
auto* header = data->mutable_header();
double timestamp =
apollo::common::time::ToSecond(apollo::common::time::Clock::Now());
header->set_module_name(module_name);
......@@ -235,7 +247,9 @@ class Adapter {
header->set_sequence_num(++seq_num_);
}
uint32_t GetSeqNum() const { return seq_num_; }
uint32_t GetSeqNum() const {
return seq_num_;
}
private:
template <typename T>
......
......@@ -71,9 +71,11 @@ namespace adapter {
static void Publish##name(const name##Adapter::DataType &data) { \
instance()->InternalPublish##name(data); \
} \
static void Fill##name##Header(const std::string &module_name, \
apollo::common::Header *header) { \
instance()->name##_->FillHeader(module_name, header); \
template <typename T> \
static void Fill##name##Header(const std::string &module_name, T *data) { \
static_assert(std::is_same<name##Adapter::DataType, T>::value, \
"Data type must be the same with adapter's type!"); \
instance()->name##_->FillHeader(module_name, data); \
} \
static void Set##name##Callback(name##Adapter::Callback callback) { \
CHECK(instance()->name##_) \
......@@ -108,7 +110,9 @@ namespace adapter {
\
observers_.push_back([this]() { name##_->Observe(); }); \
} \
name##Adapter *InternalGet##name() { return name##_.get(); } \
name##Adapter *InternalGet##name() { \
return name##_.get(); \
} \
void InternalPublish##name(const name##Adapter::DataType &data) { \
name##publisher_.publish(data); \
}
......
......@@ -44,7 +44,7 @@ void Monitor::Publish(const std::vector<MessageItem> &messages) const {
}
void Monitor::DoPublish(MonitorMessage *message) const {
AdapterManager::FillMonitorHeader("monitor", message->mutable_header());
AdapterManager::FillMonitorHeader("monitor", message);
AdapterManager::PublishMonitor(*message);
}
......
......@@ -293,8 +293,7 @@ Status Control::CheckTimestamp() {
void Control::SendCmd(ControlCommand *control_command) {
// set header
AdapterManager::FillControlCommandHeader(Name(),
control_command->mutable_header());
AdapterManager::FillControlCommandHeader(Name(), control_command);
ADEBUG << control_command->ShortDebugString();
if (FLAGS_is_control_test_mode) {
......
......@@ -50,16 +50,16 @@ void help() {
}
void send(int cmd_type) {
::apollo::control::PadMessage pb;
::apollo::control::PadMessage pad;
if (cmd_type == RESET_COMMAND) {
pb.set_action(apollo::control::DrivingAction::RESET);
pad.set_action(apollo::control::DrivingAction::RESET);
AINFO << "sending reset action command.";
} else if (cmd_type == AUTO_DRIVE_COMMAND) {
pb.set_action(apollo::control::DrivingAction::START);
pad.set_action(apollo::control::DrivingAction::START);
AINFO << "sending start action command.";
}
AdapterManager::FillPadHeader("terminal", pb.mutable_header());
AdapterManager::PublishPad(pb);
AdapterManager::FillPadHeader("terminal", &pad);
AdapterManager::PublishPad(pad);
AINFO << "send pad_message OK";
}
......
......@@ -48,7 +48,7 @@ void Decision::OnTimer(const ros::TimerEvent &) { PublishDecision(); }
void Decision::PublishDecision() {
DecisionResult decision_result;
AdapterManager::FillDecisionHeader(Name(), decision_result.mutable_header());
AdapterManager::FillDecisionHeader(Name(), &decision_result);
AdapterManager::PublishDecision(decision_result);
}
......
......@@ -172,7 +172,7 @@ void SimControl::TimerCallback(const ros::TimerEvent& event) {
void SimControl::PublishChassis(double lambda) {
Chassis chassis;
AdapterManager::FillChassisHeader("SimControl", chassis.mutable_header());
AdapterManager::FillChassisHeader("SimControl", &chassis);
chassis.set_engine_started(true);
chassis.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
......@@ -188,8 +188,7 @@ void SimControl::PublishChassis(double lambda) {
void SimControl::PublishLocalization(double lambda) {
LocalizationEstimate localization;
AdapterManager::FillLocalizationHeader("SimControl",
localization.mutable_header());
AdapterManager::FillLocalizationHeader("SimControl", &localization);
auto* pose = localization.mutable_pose();
auto prev = prev_point_.path_point();
......
......@@ -47,11 +47,11 @@ namespace {
static constexpr char kHMIRosNodeName[] = "hmi_ros_node_service";
void SendPadMessage(DrivingAction action) {
control::PadMessage pb;
pb.set_action(action);
AINFO << "Sending PadMessage:\n" << pb.DebugString();
AdapterManager::FillPadHeader(kHMIRosNodeName, pb.mutable_header());
AdapterManager::PublishPad(pb);
control::PadMessage pad;
pad.set_action(action);
AINFO << "Sending PadMessage:\n" << pad.DebugString();
AdapterManager::FillPadHeader(kHMIRosNodeName, &pad);
AdapterManager::PublishPad(pad);
}
/**
......
......@@ -142,7 +142,7 @@ bool CameraLocalization::CreateLocalizationMsg(
// header
AdapterManager::FillLocalizationHeader(FLAGS_localization_module_name,
localization->mutable_header());
localization);
if (FLAGS_enable_gps_timestamp) {
// copy time stamp, do NOT use Clock::Now()
localization->mutable_header()->set_timestamp_sec(
......
......@@ -255,7 +255,7 @@ void RTKLocalization::ComposeLocalizationMsg(
// header
AdapterManager::FillLocalizationHeader(FLAGS_localization_module_name,
localization->mutable_header());
localization);
if (FLAGS_enable_gps_timestamp) {
// copy time stamp, do NOT use Clock::Now()
localization->mutable_header()->set_timestamp_sec(
......
......@@ -245,8 +245,7 @@ void Planning::RunOnce() {
ADEBUG << "Planning latency: " << trajectory_pb.latency_stats().DebugString();
if (res_planning) {
AdapterManager::FillPlanningHeader("planning",
trajectory_pb.mutable_header());
AdapterManager::FillPlanningHeader("planning", &trajectory_pb);
trajectory_pb.mutable_header()->set_timestamp_sec(execution_start_time);
AdapterManager::PublishPlanning(trajectory_pb);
ADEBUG << "Planning succeeded:" << trajectory_pb.header().DebugString();
......
......@@ -120,8 +120,7 @@ void Prediction::OnPerception(const PerceptionObstacles &perception_obstacles) {
PredictionObstacles prediction_obstacles;
prediction_obstacles.CopyFrom(
PredictorManager::instance()->prediction_obstacles());
AdapterManager::FillPredictionHeader(
Name(), prediction_obstacles.mutable_header());
AdapterManager::FillPredictionHeader(Name(), &prediction_obstacles);
AdapterManager::PublishPrediction(prediction_obstacles);
ADEBUG << "Published a prediction message ["
<< prediction_obstacles.ShortDebugString() << "].";
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册