• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

RobotWebTools / rclnodejs / 20453082669

23 Dec 2025 06:14AM UTC coverage: 80.448% (-0.006%) from 80.454%
20453082669

Pull #1354

github

web-flow
Merge 70b1f7b98 into afeeae494
Pull Request #1354: Add ClockEvent support

1260 of 1751 branches covered (71.96%)

Branch coverage included in aggregate %.

37 of 41 new or added lines in 3 files covered. (90.24%)

6 existing lines in 1 file now uncovered.

2723 of 3200 relevant lines covered (85.09%)

465.67 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

75.25
/lib/clock.js
1
// Copyright (c) 2018 Intel Corporation. All rights reserved.
2
//
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
// you may not use this file except in compliance with the License.
5
// You may obtain a copy of the License at
6
//
7
//     http://www.apache.org/licenses/LICENSE-2.0
8
//
9
// Unless required by applicable law or agreed to in writing, software
10
// distributed under the License is distributed on an "AS IS" BASIS,
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
// See the License for the specific language governing permissions and
13
// limitations under the License.
14

15
'use strict';
16

17
const rclnodejs = require('./native_loader.js');
26✔
18
const Time = require('./time.js');
26✔
19
const ClockType = require('./clock_type.js');
26✔
20
const ClockChange = require('./clock_change.js');
26✔
21
const { TypeValidationError } = require('./errors.js');
26✔
22

23
/**
24
 * @class - Class representing a Clock in ROS
25
 */
26

27
class Clock {
28
  /**
29
   * Create a Clock.
30
   * @param {ClockType} [clockType=Clock.ClockType.SYSTEM_TIME] - The type of the clock to be created.
31
   */
32
  constructor(clockType = ClockType.SYSTEM_TIME) {
1✔
33
    this._clockType = clockType;
823✔
34
    this._handle = rclnodejs.createClock(this._clockType);
823✔
35
  }
36

37
  /**
38
   * @ignore
39
   */
40
  get handle() {
41
    return this._handle;
132✔
42
  }
43

44
  /**
45
   * Get ClockType of this Clock object.
46
   * @return {ClockType} Return the type of the clock.
47
   */
48
  get clockType() {
49
    return this._clockType;
4✔
50
  }
51

52
  /**
53
   * Add a clock callback.
54
   * @param {object} callbackObject - The object containing callback methods.
55
   * @param {Function} [callbackObject._pre_callback] - Optional callback invoked before a time jump. Takes no arguments.
56
   * @param {Function} [callbackObject._post_callback] - Optional callback invoked after a time jump.
57
   *   Receives a jumpInfo object with properties:
58
   *   - clock_change {number}: Type of clock change that occurred.
59
   *   - delta {bigint}: Time delta in nanoseconds.
60
   * @param {boolean} onClockChange - Whether to call the callback on clock change.
61
   * @param {bigint} minForward - Minimum forward jump in nanoseconds to trigger the callback.
62
   * @param {bigint} minBackward - Minimum backward jump in nanoseconds to trigger the callback.
63
   */
64
  addClockCallback(callbackObject, onClockChange, minForward, minBackward) {
65
    if (typeof callbackObject !== 'object' || callbackObject === null) {
14!
UNCOV
66
      throw new TypeValidationError(
×
67
        'callbackObject',
68
        callbackObject,
69
        'object',
70
        {
71
          entityType: 'clock',
72
        }
73
      );
74
    }
75
    if (typeof onClockChange !== 'boolean') {
14!
UNCOV
76
      throw new TypeValidationError('onClockChange', onClockChange, 'boolean', {
×
77
        entityType: 'clock',
78
      });
79
    }
80
    if (typeof minForward !== 'bigint') {
14!
UNCOV
81
      throw new TypeValidationError('minForward', minForward, 'bigint', {
×
82
        entityType: 'clock',
83
      });
84
    }
85
    if (typeof minBackward !== 'bigint') {
14!
UNCOV
86
      throw new TypeValidationError('minBackward', minBackward, 'bigint', {
×
87
        entityType: 'clock',
88
      });
89
    }
90
    rclnodejs.clockAddJumpCallback(
14✔
91
      this._handle,
92
      callbackObject,
93
      onClockChange,
94
      minForward,
95
      minBackward
96
    );
97
  }
98

99
  /**
100
   * Remove a clock callback.
101
   * @param {object} callbackObject - The callback object that was previously registered with addClockCallback().
102
   */
103
  removeClockCallback(callbackObject) {
104
    if (typeof callbackObject !== 'object' || callbackObject === null) {
15!
UNCOV
105
      throw new TypeValidationError(
×
106
        'callbackObject',
107
        callbackObject,
108
        'object',
109
        {
110
          entityType: 'clock',
111
        }
112
      );
113
    }
114
    rclnodejs.clockRemoveJumpCallback(this._handle, callbackObject);
15✔
115
  }
116

117
  /**
118
   * Return the current time.
119
   * @return {Time} Return the current time.
120
   */
121
  now() {
122
    const nowInNanosec = rclnodejs.clockGetNow(this._handle);
2,261✔
123
    return new Time(0n, nowInNanosec, this._clockType);
2,261✔
124
  }
125

126
  /**
127
   * Sleep until a specific time is reached on this Clock.
128
   *
129
   * When using a ROSClock, this may sleep forever if the TimeSource is misconfigured
130
   * and the context is never shut down. ROS time being activated or deactivated causes
131
   * this function to cease sleeping and return false.
132
   *
133
   * @param {Time} until - Time at which this function should stop sleeping.
134
   * @param {Context} [context=null] - Context which when shut down will cause this sleep to wake early.
135
   *   If context is null, then the default context is used.
136
   * @return {Promise<boolean>} Promise that resolves to true if 'until' was reached,
137
   *   or false if it woke for another reason (time jump, context shutdown).
138
   * @throws {TypeError} if until is specified for a different type of clock than this one.
139
   * @throws {Error} if context has not been initialized or is shutdown.
140
   */
141
  async sleepUntil(until, context = null) {
4✔
142
    const ClockEvent = require('./clock_event.js');
10✔
143
    const Context = require('./context.js');
10✔
144

145
    if (!context) {
10✔
146
      context = Context.defaultContext();
9✔
147
    }
148

149
    if (!context.isValid()) {
10✔
150
      throw new Error('Context is not initialized or has been shut down');
1✔
151
    }
152

153
    if (until.clockType !== this._clockType) {
9✔
154
      throw new TypeError(
1✔
155
        "until's clock type does not match this clock's type"
156
      );
157
    }
158

159
    const event = new ClockEvent();
8✔
160
    let timeSourceChanged = false;
8✔
161

162
    // Callback to wake when time jumps and is past target time
163
    const callbackObject = {
8✔
164
      _pre_callback: () => {
165
        // Optional pre-callback - no action needed
166
      },
167
      _post_callback: (jumpInfo) => {
168
        // ROS time being activated or deactivated changes the epoch,
169
        // so sleep time loses its meaning
NEW
170
        timeSourceChanged =
×
171
          timeSourceChanged ||
×
172
          jumpInfo.clock_change === ClockChange.ROS_TIME_ACTIVATED ||
173
          jumpInfo.clock_change === ClockChange.ROS_TIME_DEACTIVATED;
174

NEW
175
        if (timeSourceChanged || this.now().nanoseconds >= until.nanoseconds) {
×
NEW
176
          event.set();
×
177
        }
178
      },
179
    };
180

181
    // Setup jump callback with minimal forward threshold
182
    this.addClockCallback(
8✔
183
      callbackObject,
184
      true, // onClockChange
185
      1n, // minForward (1 nanosecond - any forward jump triggers)
186
      0n // minBackward (0 disables backward threshold)
187
    );
188

189
    try {
8✔
190
      // Wait based on clock type
191
      if (this._clockType === ClockType.SYSTEM_TIME) {
8✔
192
        await event.waitUntilSystem(this, until.nanoseconds);
2✔
193
      } else if (this._clockType === ClockType.STEADY_TIME) {
6✔
194
        await event.waitUntilSteady(this, until.nanoseconds);
4✔
195
      } else if (this._clockType === ClockType.ROS_TIME) {
2!
196
        await event.waitUntilRos(this, until.nanoseconds);
2✔
197
      }
198
    } finally {
199
      // Always clean up callback
200
      this.removeClockCallback(callbackObject);
8✔
201
    }
202

203
    if (!context.isValid() || timeSourceChanged) {
8!
NEW
204
      return false;
×
205
    }
206

207
    return this.now().nanoseconds >= until.nanoseconds;
8✔
208
  }
209

210
  /**
211
   * Sleep for a specified duration.
212
   *
213
   * Equivalent to: clock.sleepUntil(clock.now() + duration, context)
214
   *
215
   * When using a ROSClock, this may sleep forever if the TimeSource is misconfigured
216
   * and the context is never shut down. ROS time being activated or deactivated causes
217
   * this function to cease sleeping and return false.
218
   *
219
   * @param {Duration} duration - Duration of time to sleep for.
220
   * @param {Context} [context=null] - Context which when shut down will cause this sleep to wake early.
221
   *   If context is null, then the default context is used.
222
   * @return {Promise<boolean>} Promise that resolves to true if the full duration was slept,
223
   *   or false if it woke for another reason.
224
   * @throws {Error} if context has not been initialized or is shutdown.
225
   */
226
  async sleepFor(duration, context = null) {
5✔
227
    const until = this.now().add(duration);
6✔
228
    return this.sleepUntil(until, context);
6✔
229
  }
230
}
231

232
/**
233
 * @class - Class representing a ROSClock in ROS
234
 */
235

236
class ROSClock extends Clock {
237
  /**
238
   * Create a ROSClock.
239
   */
240
  constructor() {
241
    super(ClockType.ROS_TIME);
806✔
242
  }
243

244
  /**
245
   * Return status that whether the ROS time is active.
246
   * @name ROSClock#get:isRosTimeActive
247
   * @function
248
   * @return {boolean} Return true if the time is active, otherwise return false.
249
   */
250

251
  get isRosTimeActive() {
252
    return rclnodejs.getRosTimeOverrideIsEnabled(this._handle);
3✔
253
  }
254

255
  /**
256
   * Set the status of ROS time.
257
   * @param {boolean} enabled - Set the ROS time to be active.
258
   * @name ROSClock#set:isRosTimeActive
259
   * @function
260
   * @return {undefined}
261
   */
262

263
  set isRosTimeActive(enabled) {
264
    rclnodejs.setRosTimeOverrideIsEnabled(this._handle, enabled);
807✔
265
  }
266

267
  /**
268
   * Set the status of ROS time.
269
   * @param {Time} time - The time to be set override.
270
   * @name ROSClock#set:rosTimeOverride
271
   * @function
272
   * @return {undefined}
273
   */
274

275
  set rosTimeOverride(time) {
276
    if (!(time instanceof Time)) {
808!
UNCOV
277
      throw new TypeValidationError('time', time, 'Time', {
×
278
        entityType: 'clock',
279
      });
280
    }
281
    rclnodejs.setRosTimeOverride(this._handle, time._handle);
808✔
282
  }
283
}
284

285
Clock.ClockType = ClockType;
26✔
286

287
module.exports = { Clock, ROSClock };
26✔
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc