Skip to content

Commit

Permalink
framework: fix static initialization order issue during exit
Browse files Browse the repository at this point in the history
  • Loading branch information
GoLancer authored and Jiangtao Hu committed Dec 13, 2018
1 parent 6f363fc commit 8f69831
Show file tree
Hide file tree
Showing 54 changed files with 70 additions and 83 deletions.
19 changes: 9 additions & 10 deletions cyber/common/macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,15 @@
classname(const classname &) = delete; \
classname &operator=(const classname &) = delete;

#define DECLARE_SINGLETON(classname) \
public: \
static const std::shared_ptr<classname> &Instance() { \
static auto instance = \
std::shared_ptr<classname>(new (std::nothrow) classname()); \
return instance; \
} \
\
private: \
classname(); \
#define DECLARE_SINGLETON(classname) \
public: \
static classname *Instance() { \
static auto instance = new (std::nothrow) classname(); \
return instance; \
} \
\
private: \
classname(); \
DISALLOW_COPY_AND_ASSIGN(classname)

#endif // CYBER_COMMON_MACROS_H_
2 changes: 1 addition & 1 deletion cyber/data/data_dispatcher.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class DataDispatcher {
bool Dispatch(const uint64_t channel_id, const std::shared_ptr<T>& msg);

private:
std::shared_ptr<DataNotifier> notifier_ = DataNotifier::Instance();
DataNotifier* notifier_ = DataNotifier::Instance();
std::mutex buffers_map_mutex_;
AtomicHashMap<uint64_t, BufferVector> buffers_map_;

Expand Down
2 changes: 1 addition & 1 deletion cyber/data/data_visitor_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class DataVisitorBase {
DataVisitorBase& operator=(const DataVisitorBase&) = delete;

uint64_t next_msg_index_ = 0;
std::shared_ptr<DataNotifier> data_notifier_ = DataNotifier::Instance();
DataNotifier* data_notifier_ = DataNotifier::Instance();
std::shared_ptr<Notifier> notifier_;
};

Expand Down
2 changes: 1 addition & 1 deletion cyber/service_discovery/topology_manager_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class TopologyTest : public ::testing::Test {

virtual void TearDown() {}

std::shared_ptr<TopologyManager> topology_;
TopologyManager* topology_;
};

TEST_F(TopologyTest, add_and_remove_change_listener) {
Expand Down
2 changes: 1 addition & 1 deletion cyber/timer/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class Timer {

private:
TimerOption timer_opt_;
std::shared_ptr<TimerManager> tm_ = nullptr;
TimerManager* tm_ = nullptr;
uint64_t timer_id_ = 0;
};

Expand Down
12 changes: 6 additions & 6 deletions cyber/timer/timer_manager_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ namespace apollo {
namespace cyber {

TEST(TimerManagerTest, Basic) {
std::shared_ptr<TimerManager> tm_ = TimerManager::Instance();
ASSERT_EQ(tm_->IsRunning(), false);
tm_->Start();
ASSERT_EQ(tm_->IsRunning(), true);
tm_->Shutdown();
ASSERT_EQ(tm_->IsRunning(), false);
auto tm = TimerManager::Instance();
ASSERT_EQ(tm->IsRunning(), false);
tm->Start();
ASSERT_EQ(tm->IsRunning(), true);
tm->Shutdown();
ASSERT_EQ(tm->IsRunning(), false);
}

} // namespace cyber
Expand Down
2 changes: 1 addition & 1 deletion cyber/transport/dispatcher/intra_dispatcher.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ namespace cyber {
namespace transport {

class IntraDispatcher;
using IntraDispatcherPtr = std::shared_ptr<IntraDispatcher>;
using IntraDispatcherPtr = IntraDispatcher*;

class IntraDispatcher : public Dispatcher {
public:
Expand Down
4 changes: 0 additions & 4 deletions cyber/transport/dispatcher/intra_dispatcher_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,6 @@ namespace apollo {
namespace cyber {
namespace transport {

TEST(IntraDispatcherTest, constructor) {
auto dispatcher = IntraDispatcher::Instance();
}

TEST(IntraDispatcherTest, on_message) {
auto dispatcher = IntraDispatcher::Instance();

Expand Down
10 changes: 5 additions & 5 deletions cyber/transport/dispatcher/rtps_dispatcher.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ struct Subscriber {
};

class RtpsDispatcher;
using RtpsDispatcherPtr = std::shared_ptr<RtpsDispatcher>;
using RtpsDispatcherPtr = RtpsDispatcher*;

class RtpsDispatcher : public Dispatcher {
public:
Expand Down Expand Up @@ -82,8 +82,8 @@ template <typename MessageT>
void RtpsDispatcher::AddListener(const RoleAttributes& self_attr,
const MessageListener<MessageT>& listener) {
auto listener_adapter = [listener](
const std::shared_ptr<std::string>& msg_str,
const MessageInfo& msg_info) {
const std::shared_ptr<std::string>& msg_str,
const MessageInfo& msg_info) {
auto msg = std::make_shared<MessageT>();
RETURN_IF(!message::ParseFromString(*msg_str, msg.get()));
listener(msg, msg_info);
Expand All @@ -98,8 +98,8 @@ void RtpsDispatcher::AddListener(const RoleAttributes& self_attr,
const RoleAttributes& opposite_attr,
const MessageListener<MessageT>& listener) {
auto listener_adapter = [listener](
const std::shared_ptr<std::string>& msg_str,
const MessageInfo& msg_info) {
const std::shared_ptr<std::string>& msg_str,
const MessageInfo& msg_info) {
auto msg = std::make_shared<MessageT>();
RETURN_IF(!message::ParseFromString(*msg_str, msg.get()));
listener(msg, msg_info);
Expand Down
5 changes: 0 additions & 5 deletions cyber/transport/dispatcher/rtps_dispatcher_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,6 @@ namespace apollo {
namespace cyber {
namespace transport {

TEST(RtpsDispatcherTest, constructor) {
auto dispatcher = RtpsDispatcher::Instance();
// EXPECT_EQ(dispatcher->NumberOfChannel(), 0);
}

TEST(RtpsDispatcherTest, add_listener) {
auto dispatcher = RtpsDispatcher::Instance();
RoleAttributes self_attr;
Expand Down
2 changes: 1 addition & 1 deletion cyber/transport/dispatcher/shm_dispatcher.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace cyber {
namespace transport {

class ShmDispatcher;
using ShmDispatcherPtr = std::shared_ptr<ShmDispatcher>;
using ShmDispatcherPtr = ShmDispatcher*;
using apollo::cyber::base::AtomicRWLock;
using apollo::cyber::base::ReadLockGuard;
using apollo::cyber::base::WriteLockGuard;
Expand Down
4 changes: 0 additions & 4 deletions cyber/transport/dispatcher/shm_dispatcher_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,6 @@ namespace apollo {
namespace cyber {
namespace transport {

TEST(ShmDispatcherTest, constructor) {
auto dispatcher = ShmDispatcher::Instance();
}

TEST(ShmDispatcherTest, add_listener) {
auto dispatcher = ShmDispatcher::Instance();
RoleAttributes self_attr;
Expand Down
2 changes: 1 addition & 1 deletion cyber/transport/shm/notifier_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace cyber {
namespace transport {

class NotifierBase;
using NotifierPtr = std::shared_ptr<NotifierBase>;
using NotifierPtr = NotifierBase*;

class NotifierBase {
public:
Expand Down
2 changes: 1 addition & 1 deletion modules/common/monitor_log/monitor_log_buffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class MonitorLogBuffer {
void Publish();

private:
std::shared_ptr<MonitorLogger> logger_ = MonitorLogger::Instance();
MonitorLogger* logger_ = MonitorLogger::Instance();
MonitorMessageItem::LogLevel level_ = MonitorMessageItem::INFO;
std::vector<MessageItem> monitor_msg_items_;
MonitorMessageItem::MessageSource source_;
Expand Down
2 changes: 1 addition & 1 deletion modules/drivers/velodyne/compensator/compensator.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class Compensator {

bool IsValid(const Eigen::Vector3d& point);

std::shared_ptr<Buffer> tf2_buffer_ptr_ = transform::Buffer::Instance();
Buffer* tf2_buffer_ptr_ = transform::Buffer::Instance();
CompensatorConfig config_;
};

Expand Down
2 changes: 1 addition & 1 deletion modules/drivers/velodyne/fusion/pri_sec_fusion_component.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class PriSecFusionComponent : public Component<PointCloud> {
const Eigen::Affine3d& pose);

FusionConfig conf_;
std::shared_ptr<apollo::transform::Buffer> buffer_ptr_;
apollo::transform::Buffer* buffer_ptr_ = nullptr;
std::shared_ptr<Writer<PointCloud>> fusion_writer_;
std::vector<std::shared_ptr<Reader<PointCloud>>> readers_;
};
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/hardware/gps_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ GpsMonitor::GpsMonitor() : RecurrentRunner(FLAGS_gps_monitor_name,
}

void GpsMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
Component* component = apollo::common::util::FindOrNull(
*manager->GetStatus()->mutable_components(), FLAGS_gps_component_name);
if (component == nullptr) {
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/hardware/resource_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ ResourceMonitor::ResourceMonitor()
}

void ResourceMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
const auto& mode = manager->GetHMIMode();
auto* components = manager->GetStatus()->mutable_components();
for (const auto& iter : mode.monitored_components()) {
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/hardware/socket_can_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ SocketCanMonitor::SocketCanMonitor() :
}

void SocketCanMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
Component* component = apollo::common::util::FindOrNull(
*manager->GetStatus()->mutable_components(),
FLAGS_socket_can_component_name);
Expand Down
4 changes: 2 additions & 2 deletions modules/monitor/software/channel_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ using apollo::common::util::StrCat;
// We have to specify exact type of each channel. This function is a wrapper for
// those only need a ReaderBase.
std::shared_ptr<cyber::ReaderBase> GetReader(const std::string& channel) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
if (channel == FLAGS_control_command_topic) {
return manager->CreateReader<control::ControlCommand>(channel);
} else if (channel == FLAGS_localization_topic) {
Expand Down Expand Up @@ -81,7 +81,7 @@ ChannelMonitor::ChannelMonitor()
}

void ChannelMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
const auto& mode = manager->GetHMIMode();
auto* components = manager->GetStatus()->mutable_components();
for (const auto& iter : mode.monitored_components()) {
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/software/functional_safety_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void FunctionalSafetyMonitor::RunOnce(const double current_time) {

bool FunctionalSafetyMonitor::CheckSafety() {
// We only check safety in self driving mode.
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
if (!manager->IsInAutonomousMode()) {
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/software/localization_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ LocalizationMonitor::LocalizationMonitor()
FLAGS_localization_monitor_interval) {}

void LocalizationMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
auto* component = apollo::common::util::FindOrNull(
*manager->GetStatus()->mutable_components(),
FLAGS_localization_component_name);
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/software/process_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ void ProcessMonitor::RunOnce(const double current_time) {
}
}

auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
const auto& mode = manager->GetHMIMode();

// Check HMI modules.
Expand Down
2 changes: 1 addition & 1 deletion modules/monitor/software/summary_monitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ SummaryMonitor::SummaryMonitor()
}

void SummaryMonitor::RunOnce(const double current_time) {
auto& manager = MonitorManager::Instance();
auto manager = MonitorManager::Instance();
auto* status = manager->GetStatus();
// Escalate the summary status to the most severe one.
for (auto& component : *status->mutable_components()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class ConfigManagerTest : public testing::Test {
}

protected:
std::shared_ptr<ConfigManager> config_manager_;
ConfigManager* config_manager_;
};

TEST_F(ConfigManagerTest, TestInit) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace lidar {
bool LidarObstacleSegmentation::Init(
const LidarObstacleSegmentationInitOptions& options) {
auto& sensor_name = options.sensor_name;
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));

Expand Down
2 changes: 1 addition & 1 deletion modules/perception/lidar/app/lidar_obstacle_tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace lidar {
bool LidarObstacleTracking::Init(
const LidarObstacleTrackingInitOptions& options) {
auto& sensor_name = options.sensor_name;
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ using apollo::common::util::GetAbsolutePath;
using apollo::perception::base::ObjectType;

bool CCRFOneShotTypeFusion::Init(const TypeFusionInitOption& option) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down Expand Up @@ -128,7 +128,7 @@ bool CCRFOneShotTypeFusion::FuseOneShotTypeProbs(const ObjectPtr& object,

bool CCRFSequenceTypeFusion::Init(const TypeFusionInitOption& option) {
CHECK(one_shot_fuser_.Init(option));
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ using apollo::common::util::GetAbsolutePath;
using apollo::perception::base::ObjectType;

bool FusedClassifier::Init(const ClassifierInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace lidar {
using apollo::common::util::GetAbsolutePath;

bool GroundServiceDetector::Init(const GroundDetectorInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();

const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ using apollo::common::util::GetProtoFromFile;
bool SpatioTemporalGroundDetector::Init(
const GroundDetectorInitOptions& options) {
const lib::ModelConfig* model_config = nullptr;
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
CHECK(config_manager->GetModelConfig(
"SpatioTemporalGroundDetector", &model_config))
<< "Failed to get model config: SpatioTemporalGroundDetector";
Expand Down
2 changes: 1 addition & 1 deletion modules/perception/lidar/lib/map_manager/map_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace lidar {
using apollo::common::util::GetAbsolutePath;

bool MapManager::Init(const MapManagerInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace lidar {
using apollo::common::util::GetAbsolutePath;

bool ObjectFilterBank::Init(const ObjectFilterInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using apollo::common::util::GetAbsolutePath;
using apollo::perception::base::PointD;

bool ROIBoundaryFilter::Init(const ObjectFilterInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ const float PointCloudPreprocessor::kPointInfThreshold = 1e3;

bool PointCloudPreprocessor::Init(
const PointCloudPreprocessorInitOptions& options) {
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ using Polygon = typename PolygonScanCvter<T>::Polygon;

bool HdmapROIFilter::Init(const ROIFilterInitOptions& options) {
// load model config
auto& config_manager = lib::ConfigManager::Instance();
auto config_manager = lib::ConfigManager::Instance();
const lib::ModelConfig* model_config = nullptr;
CHECK(config_manager->GetModelConfig(Name(), &model_config));
const std::string work_root = config_manager->work_root();
Expand Down
Loading

0 comments on commit 8f69831

Please sign in to comment.