Apollo 10.0
自动驾驶开放平台
apollo::cyber::Clock类 参考

a singleton clock that can be used to get the current timestamp. 更多...

#include <clock.h>

apollo::cyber::Clock 的协作图:

静态 Public 成员函数

static Time Now ()
 PRECISION >= 1000000 means the precision is at least 1us.
 
static double NowInSeconds ()
 gets the current time in second.
 
static void SetNow (const Time &now)
 This is for mock clock mode only.
 
static void SetMode (ClockMode mode)
 
static ClockMode mode ()
 Gets the current clock mode.
 
static void SetNowInSeconds (const double seconds)
 This is for mock clock mode only.
 

静态 Public 属性

static constexpr int64_t PRECISION
 

详细描述

a singleton clock that can be used to get the current timestamp.

The source can be either system(cyber) clock or a mock clock. Mock clock is for testing purpose mainly.

在文件 clock.h39 行定义.

成员函数说明

◆ mode()

ClockMode Clock::mode ( )
static

Gets the current clock mode.

返回
The current clock mode.

在文件 clock.cc76 行定义.

76 {
77 auto clock = Instance();
78 AtomicReadLockGuard lg(clock->rwlock_);
79 return clock->mode_;
80}
::apollo::cyber::base::ReadLockGuard< AtomicRWLock > AtomicReadLockGuard
Definition clock.cc:31

◆ Now()

Time Clock::Now ( )
static

PRECISION >= 1000000 means the precision is at least 1us.

get current time.

返回
a Time object representing the current time.

在文件 clock.cc40 行定义.

40 {
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}
static Time Now()
get the current time.
Definition time.cc:57
#define AFATAL
Definition log.h:45
auto ToInt(Enum const value) -> typename std::underlying_type< Enum >::type
Definition util.h:32

◆ NowInSeconds()

double Clock::NowInSeconds ( )
static

gets the current time in second.

返回
the current time in second.

在文件 clock.cc56 行定义.

56{ return Now().ToSecond(); }
static Time Now()
PRECISION >= 1000000 means the precision is at least 1us.
Definition clock.cc:40
double ToSecond() const
convert time to second.
Definition time.cc:77

◆ SetMode()

void Clock::SetMode ( ClockMode  mode)
static

在文件 clock.cc58 行定义.

58 {
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}
static ClockMode mode()
Gets the current clock mode.
Definition clock.cc:76
Cyber has builtin time type Time.
Definition time.h:31
#define AERROR
Definition log.h:44
::apollo::cyber::base::WriteLockGuard< AtomicRWLock > AtomicWriteLockGuard
Definition clock.cc:30

◆ SetNow()

void Clock::SetNow ( const Time now)
static

This is for mock clock mode only.

It will set the timestamp for the mock clock.

在文件 clock.cc82 行定义.

82 {
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}

◆ SetNowInSeconds()

static void apollo::cyber::Clock::SetNowInSeconds ( const double  seconds)
inlinestatic

This is for mock clock mode only.

It will set the timestamp for the mock clock with UNIX timestamp in seconds.

在文件 clock.h84 行定义.

84 {
85 Clock::SetNow(Time(seconds));
86 }
static void SetNow(const Time &now)
This is for mock clock mode only.
Definition clock.cc:82

类成员变量说明

◆ PRECISION

constexpr int64_t apollo::cyber::Clock::PRECISION
staticconstexpr
初始值:
=
std::chrono::system_clock::duration::period::den /
std::chrono::system_clock::duration::period::num

在文件 clock.h41 行定义.


该类的文档由以下文件生成: