Apollo 10.0
自动驾驶开放平台
clock.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2020 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
17#include "cyber/time/clock.h"
18
20#include "cyber/common/log.h"
21#include "cyber/common/util.h"
22
23namespace apollo {
24namespace cyber {
25
27
32
33Clock::Clock() {
34 const auto& cyber_config = GlobalData::Instance()->Config();
35 const auto& clock_mode = cyber_config.run_mode_conf().clock_mode();
36 mode_ = clock_mode;
37 mock_now_ = Time(0);
38}
39
41 auto clock = Instance();
42
43 AtomicReadLockGuard lg(clock->rwlock_);
44 switch (clock->mode_) {
45 case ClockMode::MODE_CYBER:
46 return Time::Now();
47 case ClockMode::MODE_MOCK:
48 return clock->mock_now_;
49 default:
50 AFATAL << "Unsupported clock mode: "
51 << apollo::cyber::common::ToInt(clock->mode_);
52 }
53 return Time::Now();
54}
55
56double Clock::NowInSeconds() { return Now().ToSecond(); }
57
58void Clock::SetMode(ClockMode mode) {
59 auto clock = Instance();
60 AtomicWriteLockGuard lg(clock->rwlock_);
61 switch (mode) {
62 case ClockMode::MODE_MOCK: {
63 clock->mode_ = mode;
64 break;
65 }
66 case ClockMode::MODE_CYBER: {
67 clock->mode_ = mode;
68 break;
69 }
70 default:
71 AERROR << "Unknown ClockMode: " << mode;
72 }
73 clock->mock_now_ = Time(0);
74}
75
76ClockMode Clock::mode() {
77 auto clock = Instance();
78 AtomicReadLockGuard lg(clock->rwlock_);
79 return clock->mode_;
80}
81
82void Clock::SetNow(const Time& now) {
83 auto clock = Instance();
84 AtomicWriteLockGuard lg(clock->rwlock_);
85 if (clock->mode_ != ClockMode::MODE_MOCK) {
86 AERROR << "SetSimNow only works for ClockMode::MOCK";
87 return;
88 }
89 clock->mock_now_ = now;
90}
91
92} // namespace cyber
93} // namespace apollo
static ClockMode mode()
Gets the current clock mode.
Definition clock.cc:76
static void SetMode(ClockMode mode)
Definition clock.cc:58
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
static void SetNow(const Time &now)
This is for mock clock mode only.
Definition clock.cc:82
static Time Now()
PRECISION >= 1000000 means the precision is at least 1us.
Definition clock.cc:40
Cyber has builtin time type Time.
Definition time.h:31
static Time Now()
get the current time.
Definition time.cc:57
double ToSecond() const
convert time to second.
Definition time.cc:77
#define AERROR
Definition log.h:44
#define AFATAL
Definition log.h:45
auto ToInt(Enum const value) -> typename std::underlying_type< Enum >::type
Definition util.h:32
class register implement
Definition arena_queue.h:37