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

RobotWebTools / rclnodejs / 20742259610

06 Jan 2026 08:04AM UTC coverage: 80.626% (-2.2%) from 82.843%
20742259610

push

github

minggangw
Add ClockEvent support (#1354)

This PR adds comprehensive ClockEvent support to rclnodejs, enabling clock-based sleep functionality for STEADY_TIME, SYSTEM_TIME, and ROS_TIME clocks.

### New Features

**ClockEvent Class**
- Thread-safe event synchronization for clock-based waiting
- Support for steady, system, and ROS clock types
- Async worker pattern for non-blocking sleep operations
- Clock epoch synchronization between RCL and std::chrono

**Clock Sleep Methods**
- `Clock.sleepUntil(until, context)` - Sleep until absolute time point
- `Clock.sleepFor(duration, context)` - Sleep for specified duration
- Clock jump callbacks to wake on time changes
- Context-aware early wakeup on shutdown
- Detects ROS time activation/deactivation

**ClockChange Enum**
- `ROS_TIME_NO_CHANGE`, `ROS_TIME_ACTIVATED`, `ROS_TIME_DEACTIVATED`, `SYSTEM_TIME_NO_CHANGE`
- Used in clock jump callback notifications

### Critical Fixes

**BigInt Precision Loss Prevention**
- Added lossless conversion checks for nanosecond timestamps
- Prevents silent data corruption when converting BigInt to int64_t

**Missing Module Imports**
- Fixed missing Context, ClockEvent, and ClockChange imports in clock.js

### Test Coverage

- **test-clock-event.js** - Basic ClockEvent operations (4 tests)
- **test-clock-sleep.js** - Sleep methods for all clock types (11 tests)
  - Includes comprehensive ROS time active scenario with TimeSource + simulated clock messages
- **test-clock-change.js** - ClockChange enum and integration tests (11 tests)

**Results**: 1055 passing, 6 pending

### Files Changed

**Added**: 
- `src/clock_event.{cpp,hpp}`, clock_event.js, clock_change.js
- `types/clock_event.d.ts`, `types/clock_change.d.ts`
- `test/test-clock-{event,sleep,change}.js`

**Modified**:
- clock.js - Added sleep methods and imports
- `types/clock.d.ts`, index.d.ts - Added type definitions
- `binding.gyp`, `index.js`, `src/addon.cpp` - Registered bindings

**Impact**: +1397 lines, fully backward co... (continued)

1268 of 1753 branches covered (72.33%)

Branch coverage included in aggregate %.

40 of 42 new or added lines in 3 files covered. (95.24%)

122 existing lines in 10 files now uncovered.

2727 of 3202 relevant lines covered (85.17%)

465.68 hits per line

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

87.13
/lib/node.js
1
// Copyright (c) 2017 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

19
const ActionInterfaces = require('./action/interfaces.js');
26✔
20
const Client = require('./client.js');
26✔
21
const Clock = require('./clock.js');
26✔
22
const Context = require('./context.js');
26✔
23
const debug = require('debug')('rclnodejs:node');
26✔
24
const DistroUtils = require('./distro.js');
26✔
25
const GuardCondition = require('./guard_condition.js');
26✔
26
const loader = require('./interface_loader.js');
26✔
27
const Logging = require('./logging.js');
26✔
28
const NodeOptions = require('./node_options.js');
26✔
29
const {
30
  ParameterType,
31
  Parameter,
32
  ParameterDescriptor,
33
} = require('./parameter.js');
26✔
34
const { isValidSerializationMode } = require('./message_serialization.js');
26✔
35
const {
36
  TypeValidationError,
37
  RangeValidationError,
38
  ValidationError,
39
} = require('./errors.js');
26✔
40
const ParameterService = require('./parameter_service.js');
26✔
41
const ParameterClient = require('./parameter_client.js');
26✔
42
const ParameterWatcher = require('./parameter_watcher.js');
26✔
43
const Publisher = require('./publisher.js');
26✔
44
const QoS = require('./qos.js');
26✔
45
const Rates = require('./rate.js');
26✔
46
const Service = require('./service.js');
26✔
47
const Subscription = require('./subscription.js');
26✔
48
const ObservableSubscription = require('./observable_subscription.js');
26✔
49
const TimeSource = require('./time_source.js');
26✔
50
const Timer = require('./timer.js');
26✔
51
const TypeDescriptionService = require('./type_description_service.js');
26✔
52
const Entity = require('./entity.js');
26✔
53
const { SubscriptionEventCallbacks } = require('../lib/event_handler.js');
26✔
54
const { PublisherEventCallbacks } = require('../lib/event_handler.js');
26✔
55
const { validateFullTopicName } = require('./validator.js');
26✔
56

57
// Parameter event publisher constants
58
const PARAMETER_EVENT_MSG_TYPE = 'rcl_interfaces/msg/ParameterEvent';
26✔
59
const PARAMETER_EVENT_TOPIC = 'parameter_events';
26✔
60

61
/**
62
 * @class - Class representing a Node in ROS
63
 */
64

65
class Node extends rclnodejs.ShadowNode {
66
  /**
67
   * Create a ROS2Node.
68
   * model using the {@link https://github.com/ros2/rcl/tree/master/rcl_lifecycle|ros2 client library (rcl) lifecyle api}.
69
   * @param {string} nodeName - The name used to register in ROS.
70
   * @param {string} [namespace=''] - The namespace used in ROS.
71
   * @param {Context} [context=Context.defaultContext()] - The context to create the node in.
72
   * @param {NodeOptions} [options=NodeOptions.defaultOptions] - The options to configure the new node behavior.
73
   * @throws {Error} If the given context is not registered.
74
   */
75
  constructor(
76
    nodeName,
77
    namespace = '',
44✔
78
    context = Context.defaultContext(),
79✔
79
    options = NodeOptions.defaultOptions,
81✔
80
    args = [],
100✔
81
    useGlobalArguments = true
100✔
82
  ) {
83
    super();
830✔
84

85
    if (typeof nodeName !== 'string') {
830✔
86
      throw new TypeValidationError('nodeName', nodeName, 'string');
12✔
87
    }
88
    if (typeof namespace !== 'string') {
818✔
89
      throw new TypeValidationError('namespace', namespace, 'string');
10✔
90
    }
91

92
    this._init(nodeName, namespace, options, context, args, useGlobalArguments);
808✔
93
    debug(
798✔
94
      'Finish initializing node, name = %s and namespace = %s.',
95
      nodeName,
96
      namespace
97
    );
98
  }
99

100
  _init(name, namespace, options, context, args, useGlobalArguments) {
101
    this.handle = rclnodejs.createNode(
808✔
102
      name,
103
      namespace,
104
      context.handle,
105
      args,
106
      useGlobalArguments,
107
      options.rosoutQos
108
    );
109
    Object.defineProperty(this, 'handle', {
798✔
110
      configurable: false,
111
      writable: false,
112
    }); // make read-only
113

114
    this._context = context;
798✔
115
    this.context.onNodeCreated(this);
798✔
116

117
    this._publishers = [];
798✔
118
    this._subscriptions = [];
798✔
119
    this._clients = [];
798✔
120
    this._services = [];
798✔
121
    this._timers = [];
798✔
122
    this._guards = [];
798✔
123
    this._events = [];
798✔
124
    this._actionClients = [];
798✔
125
    this._actionServers = [];
798✔
126
    this._parameterClients = [];
798✔
127
    this._parameterWatchers = [];
798✔
128
    this._rateTimerServer = null;
798✔
129
    this._parameterDescriptors = new Map();
798✔
130
    this._parameters = new Map();
798✔
131
    this._parameterService = null;
798✔
132
    this._typeDescriptionService = null;
798✔
133
    this._parameterEventPublisher = null;
798✔
134
    this._setParametersCallbacks = [];
798✔
135
    this._logger = new Logging(rclnodejs.getNodeLoggerName(this.handle));
798✔
136
    this._spinning = false;
798✔
137
    this._enableRosout = options.enableRosout;
798✔
138

139
    if (this._enableRosout) {
798✔
140
      rclnodejs.initRosoutPublisherForNode(this.handle);
797✔
141
    }
142

143
    this._parameterEventPublisher = this.createPublisher(
798✔
144
      PARAMETER_EVENT_MSG_TYPE,
145
      PARAMETER_EVENT_TOPIC
146
    );
147

148
    // initialize _parameterOverrides from parameters defined on the commandline
149
    this._parameterOverrides = this._getNativeParameterOverrides();
798✔
150

151
    // override cli parameterOverrides with those specified in options
152
    if (options.parameterOverrides.length > 0) {
798✔
153
      for (const parameter of options.parameterOverrides) {
9✔
154
        if ((!parameter) instanceof Parameter) {
14!
UNCOV
155
          throw new TypeValidationError(
×
156
            'parameterOverride',
157
            parameter,
158
            'Parameter instance',
159
            {
160
              nodeName: name,
161
            }
162
          );
163
        }
164
        this._parameterOverrides.set(parameter.name, parameter);
14✔
165
      }
166
    }
167

168
    // initialize _parameters from parameterOverrides
169
    if (options.automaticallyDeclareParametersFromOverrides) {
798✔
170
      for (const parameter of this._parameterOverrides.values()) {
5✔
171
        parameter.validate();
10✔
172
        const descriptor = ParameterDescriptor.fromParameter(parameter);
10✔
173
        this._parameters.set(parameter.name, parameter);
10✔
174
        this._parameterDescriptors.set(parameter.name, descriptor);
10✔
175
      }
176
    }
177

178
    // Clock that has support for ROS time.
179
    // Note: parameter overrides and parameter event publisher need to be ready at this point
180
    // to be able to declare 'use_sim_time' if it was not declared yet.
181
    this._clock = new Clock.ROSClock();
798✔
182
    this._timeSource = new TimeSource(this);
798✔
183
    this._timeSource.attachClock(this._clock);
798✔
184

185
    if (options.startParameterServices) {
798✔
186
      this._parameterService = new ParameterService(this);
792✔
187
      this._parameterService.start();
792✔
188
    }
189

190
    if (
798!
191
      DistroUtils.getDistroId() >= DistroUtils.getDistroId('jazzy') &&
1,596✔
192
      options.startTypeDescriptionService
193
    ) {
194
      this._typeDescriptionService = new TypeDescriptionService(this);
798✔
195
      this._typeDescriptionService.start();
798✔
196
    }
197
  }
198

199
  execute(handles) {
200
    let timersReady = this._timers.filter((timer) =>
6,684✔
201
      handles.includes(timer.handle)
5,738✔
202
    );
203
    let guardsReady = this._guards.filter((guard) =>
6,684✔
204
      handles.includes(guard.handle)
3✔
205
    );
206
    let subscriptionsReady = this._subscriptions.filter((subscription) =>
6,684✔
207
      handles.includes(subscription.handle)
524✔
208
    );
209
    let clientsReady = this._clients.filter((client) =>
6,684✔
210
      handles.includes(client.handle)
313✔
211
    );
212
    let servicesReady = this._services.filter((service) =>
6,684✔
213
      handles.includes(service.handle)
28,931✔
214
    );
215
    let actionClientsReady = this._actionClients.filter((actionClient) =>
6,684✔
216
      handles.includes(actionClient.handle)
156✔
217
    );
218
    let actionServersReady = this._actionServers.filter((actionServer) =>
6,684✔
219
      handles.includes(actionServer.handle)
156✔
220
    );
221
    let eventsReady = this._events.filter((event) =>
6,684✔
222
      handles.includes(event.handle)
4✔
223
    );
224

225
    timersReady.forEach((timer) => {
6,684✔
226
      if (timer.isReady()) {
5,728✔
227
        rclnodejs.callTimer(timer.handle);
5,665✔
228
        timer.callback();
5,665✔
229
      }
230
    });
231

232
    eventsReady.forEach((event) => {
6,684✔
233
      event.takeData();
4✔
234
    });
235

236
    for (const subscription of subscriptionsReady) {
6,684✔
237
      if (subscription.isDestroyed()) continue;
479✔
238
      if (subscription.isRaw) {
469✔
239
        let rawMessage = rclnodejs.rclTakeRaw(subscription.handle);
1✔
240
        if (rawMessage) {
1!
241
          subscription.processResponse(rawMessage);
1✔
242
        }
243
        continue;
1✔
244
      }
245

246
      this._runWithMessageType(
468✔
247
        subscription.typeClass,
248
        (message, deserialize) => {
249
          let success = rclnodejs.rclTake(subscription.handle, message);
468✔
250
          if (success) {
468✔
251
            subscription.processResponse(deserialize());
393✔
252
          }
253
        }
254
      );
255
    }
256

257
    for (const guard of guardsReady) {
6,684✔
258
      if (guard.isDestroyed()) continue;
3!
259

260
      guard.callback();
3✔
261
    }
262

263
    for (const client of clientsReady) {
6,684✔
264
      if (client.isDestroyed()) continue;
159!
265
      this._runWithMessageType(
159✔
266
        client.typeClass.Response,
267
        (message, deserialize) => {
268
          let sequenceNumber = rclnodejs.rclTakeResponse(
159✔
269
            client.handle,
270
            message
271
          );
272
          if (sequenceNumber !== undefined) {
159✔
273
            client.processResponse(sequenceNumber, deserialize());
86✔
274
          }
275
        }
276
      );
277
    }
278

279
    for (const service of servicesReady) {
6,684✔
280
      if (service.isDestroyed()) continue;
177!
281
      this._runWithMessageType(
177✔
282
        service.typeClass.Request,
283
        (message, deserialize) => {
284
          let header = rclnodejs.rclTakeRequest(
177✔
285
            service.handle,
286
            this.handle,
287
            message
288
          );
289
          if (header) {
177✔
290
            service.processRequest(header, deserialize());
91✔
291
          }
292
        }
293
      );
294
    }
295

296
    for (const actionClient of actionClientsReady) {
6,684✔
297
      if (actionClient.isDestroyed()) continue;
73!
298

299
      const properties = actionClient.handle.properties;
73✔
300

301
      if (properties.isGoalResponseReady) {
73✔
302
        this._runWithMessageType(
35✔
303
          actionClient.typeClass.impl.SendGoalService.Response,
304
          (message, deserialize) => {
305
            let sequence = rclnodejs.actionTakeGoalResponse(
35✔
306
              actionClient.handle,
307
              message
308
            );
309
            if (sequence != undefined) {
35✔
310
              actionClient.processGoalResponse(sequence, deserialize());
30✔
311
            }
312
          }
313
        );
314
      }
315

316
      if (properties.isCancelResponseReady) {
73✔
317
        this._runWithMessageType(
5✔
318
          actionClient.typeClass.impl.CancelGoal.Response,
319
          (message, deserialize) => {
320
            let sequence = rclnodejs.actionTakeCancelResponse(
5✔
321
              actionClient.handle,
322
              message
323
            );
324
            if (sequence != undefined) {
5✔
325
              actionClient.processCancelResponse(sequence, deserialize());
4✔
326
            }
327
          }
328
        );
329
      }
330

331
      if (properties.isResultResponseReady) {
73✔
332
        this._runWithMessageType(
15✔
333
          actionClient.typeClass.impl.GetResultService.Response,
334
          (message, deserialize) => {
335
            let sequence = rclnodejs.actionTakeResultResponse(
15✔
336
              actionClient.handle,
337
              message
338
            );
339
            if (sequence != undefined) {
15!
340
              actionClient.processResultResponse(sequence, deserialize());
15✔
341
            }
342
          }
343
        );
344
      }
345

346
      if (properties.isFeedbackReady) {
73✔
347
        this._runWithMessageType(
7✔
348
          actionClient.typeClass.impl.FeedbackMessage,
349
          (message, deserialize) => {
350
            let success = rclnodejs.actionTakeFeedback(
7✔
351
              actionClient.handle,
352
              message
353
            );
354
            if (success) {
7✔
355
              actionClient.processFeedbackMessage(deserialize());
5✔
356
            }
357
          }
358
        );
359
      }
360

361
      if (properties.isStatusReady) {
73✔
362
        this._runWithMessageType(
35✔
363
          actionClient.typeClass.impl.GoalStatusArray,
364
          (message, deserialize) => {
365
            let success = rclnodejs.actionTakeStatus(
35✔
366
              actionClient.handle,
367
              message
368
            );
369
            if (success) {
35✔
370
              actionClient.processStatusMessage(deserialize());
32✔
371
            }
372
          }
373
        );
374
      }
375
    }
376

377
    for (const actionServer of actionServersReady) {
6,684✔
378
      if (actionServer.isDestroyed()) continue;
92!
379

380
      const properties = actionServer.handle.properties;
92✔
381

382
      if (properties.isGoalRequestReady) {
92✔
383
        this._runWithMessageType(
32✔
384
          actionServer.typeClass.impl.SendGoalService.Request,
385
          (message, deserialize) => {
386
            const result = rclnodejs.actionTakeGoalRequest(
32✔
387
              actionServer.handle,
388
              message
389
            );
390
            if (result) {
32✔
391
              actionServer.processGoalRequest(result, deserialize());
30✔
392
            }
393
          }
394
        );
395
      }
396

397
      if (properties.isCancelRequestReady) {
92✔
398
        this._runWithMessageType(
6✔
399
          actionServer.typeClass.impl.CancelGoal.Request,
400
          (message, deserialize) => {
401
            const result = rclnodejs.actionTakeCancelRequest(
6✔
402
              actionServer.handle,
403
              message
404
            );
405
            if (result) {
6✔
406
              actionServer.processCancelRequest(result, deserialize());
4✔
407
            }
408
          }
409
        );
410
      }
411

412
      if (properties.isResultRequestReady) {
92✔
413
        this._runWithMessageType(
21✔
414
          actionServer.typeClass.impl.GetResultService.Request,
415
          (message, deserialize) => {
416
            const result = rclnodejs.actionTakeResultRequest(
21✔
417
              actionServer.handle,
418
              message
419
            );
420
            if (result) {
21✔
421
              actionServer.processResultRequest(result, deserialize());
15✔
422
            }
423
          }
424
        );
425
      }
426

427
      if (properties.isGoalExpired) {
92✔
428
        let GoalInfoArray = ActionInterfaces.GoalInfo.ArrayType;
4✔
429
        let message = new GoalInfoArray(actionServer._goalHandles.size);
4✔
430
        let count = rclnodejs.actionExpireGoals(
4✔
431
          actionServer.handle,
432
          actionServer._goalHandles.size,
433
          message._refArray.buffer
434
        );
435
        if (count > 0) {
4✔
436
          actionServer.processGoalExpired(message, count);
3✔
437
        }
438
        GoalInfoArray.freeArray(message);
4✔
439
      }
440
    }
441

442
    // At this point it is safe to clear the cache of any
443
    // destroyed entity references
444
    Entity._gcHandles();
6,684✔
445
  }
446

447
  /**
448
   * Determine if this node is spinning.
449
   * @returns {boolean} - true when spinning; otherwise returns false.
450
   */
451
  get spinning() {
452
    return this._spinning;
4,450✔
453
  }
454

455
  /**
456
   * Trigger the event loop to continuously check for and route.
457
   * incoming events.
458
   * @param {Node} node - The node to be spun up.
459
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
460
   * @throws {Error} If the node is already spinning.
461
   * @return {undefined}
462
   */
463
  spin(timeout = 10) {
17✔
464
    if (this.spinning) {
619!
UNCOV
465
      throw new Error('The node is already spinning.');
×
466
    }
467
    this.start(this.context.handle, timeout);
619✔
468
    this._spinning = true;
619✔
469
  }
470

471
  /**
472
   * Use spin().
473
   * @deprecated, since 0.18.0
474
   */
475
  startSpinning(timeout) {
UNCOV
476
    this.spin(timeout);
×
477
  }
478

479
  /**
480
   * Terminate spinning - no further events will be received.
481
   * @returns {undefined}
482
   */
483
  stop() {
484
    super.stop();
619✔
485
    this._spinning = false;
619✔
486
  }
487

488
  /**
489
   * Terminate spinning - no further events will be received.
490
   * @returns {undefined}
491
   * @deprecated since 0.18.0, Use stop().
492
   */
493
  stopSpinning() {
UNCOV
494
    super.stop();
×
UNCOV
495
    this._spinning = false;
×
496
  }
497

498
  /**
499
   * Spin the node and trigger the event loop to check for one incoming event. Thereafter the node
500
   * will not received additional events until running additional calls to spin() or spinOnce().
501
   * @param {Node} node - The node to be spun.
502
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
503
   * @throws {Error} If the node is already spinning.
504
   * @return {undefined}
505
   */
506
  spinOnce(timeout = 10) {
2✔
507
    if (this.spinning) {
3,009✔
508
      throw new Error('The node is already spinning.');
2✔
509
    }
510
    super.spinOnce(this.context.handle, timeout);
3,007✔
511
  }
512

513
  _removeEntityFromArray(entity, array) {
514
    let index = array.indexOf(entity);
341✔
515
    if (index > -1) {
341✔
516
      array.splice(index, 1);
339✔
517
    }
518
  }
519

520
  _destroyEntity(entity, array, syncHandles = true) {
287✔
521
    if (entity['isDestroyed'] && entity.isDestroyed()) return;
294✔
522

523
    this._removeEntityFromArray(entity, array);
286✔
524
    if (syncHandles) {
286✔
525
      this.syncHandles();
281✔
526
    }
527

528
    if (entity['_destroy']) {
286✔
529
      entity._destroy();
280✔
530
    } else {
531
      // guards and timers
532
      entity.handle.release();
6✔
533
    }
534
  }
535

536
  _validateOptions(options) {
537
    if (
7,473✔
538
      options !== undefined &&
7,547✔
539
      (options === null || typeof options !== 'object')
540
    ) {
541
      throw new TypeValidationError('options', options, 'object', {
20✔
542
        nodeName: this.name(),
543
      });
544
    }
545

546
    if (options === undefined) {
7,453✔
547
      return Node.getDefaultOptions();
7,426✔
548
    }
549

550
    if (options.enableTypedArray === undefined) {
27✔
551
      options = Object.assign(options, { enableTypedArray: true });
13✔
552
    }
553

554
    if (options.qos === undefined) {
27✔
555
      options = Object.assign(options, { qos: QoS.profileDefault });
13✔
556
    }
557

558
    if (options.isRaw === undefined) {
27✔
559
      options = Object.assign(options, { isRaw: false });
16✔
560
    }
561

562
    if (options.serializationMode === undefined) {
27✔
563
      options = Object.assign(options, { serializationMode: 'default' });
10✔
564
    } else if (!isValidSerializationMode(options.serializationMode)) {
17✔
565
      throw new ValidationError(
1✔
566
        `Invalid serializationMode: ${options.serializationMode}. Valid modes are: 'default', 'plain', 'json'`,
567
        {
568
          code: 'INVALID_SERIALIZATION_MODE',
569
          argumentName: 'serializationMode',
570
          providedValue: options.serializationMode,
571
          expectedType: "'default' | 'plain' | 'json'",
572
          nodeName: this.name(),
573
        }
574
      );
575
    }
576

577
    return options;
26✔
578
  }
579

580
  /**
581
   * Create a Timer.
582
   * @param {bigint} period - The number representing period in nanoseconds.
583
   * @param {function} callback - The callback to be called when timeout.
584
   * @param {Clock} [clock] - The clock which the timer gets time from.
585
   * @return {Timer} - An instance of Timer.
586
   */
587
  createTimer(period, callback, clock = null) {
62✔
588
    if (arguments.length === 3 && !(arguments[2] instanceof Clock)) {
62!
UNCOV
589
      clock = null;
×
590
    } else if (arguments.length === 4) {
62!
UNCOV
591
      clock = arguments[3];
×
592
    }
593

594
    if (typeof period !== 'bigint') {
62✔
595
      throw new TypeValidationError('period', period, 'bigint', {
1✔
596
        nodeName: this.name(),
597
      });
598
    }
599
    if (typeof callback !== 'function') {
61✔
600
      throw new TypeValidationError('callback', callback, 'function', {
1✔
601
        nodeName: this.name(),
602
      });
603
    }
604

605
    const timerClock = clock || this._clock;
60✔
606
    let timerHandle = rclnodejs.createTimer(
60✔
607
      timerClock.handle,
608
      this.context.handle,
609
      period
610
    );
611
    let timer = new Timer(timerHandle, period, callback);
60✔
612
    debug('Finish creating timer, period = %d.', period);
60✔
613
    this._timers.push(timer);
60✔
614
    this.syncHandles();
60✔
615

616
    return timer;
60✔
617
  }
618

619
  /**
620
   * Create a Rate.
621
   *
622
   * @param {number} hz - The frequency of the rate timer; default is 1 hz.
623
   * @returns {Promise<Rate>} - Promise resolving to new instance of Rate.
624
   */
625
  async createRate(hz = 1) {
4✔
626
    if (typeof hz !== 'number') {
9!
UNCOV
627
      throw new TypeValidationError('hz', hz, 'number', {
×
628
        nodeName: this.name(),
629
      });
630
    }
631

632
    const MAX_RATE_HZ_IN_MILLISECOND = 1000.0;
9✔
633
    if (hz <= 0.0 || hz > MAX_RATE_HZ_IN_MILLISECOND) {
9✔
634
      throw new RangeValidationError(
2✔
635
        'hz',
636
        hz,
637
        `0.0 < hz <= ${MAX_RATE_HZ_IN_MILLISECOND}`,
638
        {
639
          nodeName: this.name(),
640
        }
641
      );
642
    }
643

644
    // lazy initialize rateTimerServer
645
    if (!this._rateTimerServer) {
7✔
646
      this._rateTimerServer = new Rates.RateTimerServer(this);
5✔
647
      await this._rateTimerServer.init();
5✔
648
    }
649

650
    const period = Math.round(1000 / hz);
7✔
651
    const timer = this._rateTimerServer.createTimer(BigInt(period) * 1000000n);
7✔
652
    const rate = new Rates.Rate(hz, timer);
7✔
653

654
    return rate;
7✔
655
  }
656

657
  /**
658
   * Create a Publisher.
659
   * @param {function|string|object} typeClass - The ROS message class,
660
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
661
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
662
   * @param {string} topic - The name of the topic.
663
   * @param {object} options - The options argument used to parameterize the publisher.
664
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
665
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the publisher, default: QoS.profileDefault.
666
   * @param {PublisherEventCallbacks} eventCallbacks - The event callbacks for the publisher.
667
   * @return {Publisher} - An instance of Publisher.
668
   */
669
  createPublisher(typeClass, topic, options, eventCallbacks) {
670
    return this._createPublisher(
1,167✔
671
      typeClass,
672
      topic,
673
      options,
674
      Publisher,
675
      eventCallbacks
676
    );
677
  }
678

679
  _createPublisher(typeClass, topic, options, publisherClass, eventCallbacks) {
680
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
1,170✔
681
      typeClass = loader.loadInterface(typeClass);
1,146✔
682
    }
683
    options = this._validateOptions(options);
1,163✔
684

685
    if (typeof typeClass !== 'function') {
1,163✔
686
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
687
        nodeName: this.name(),
688
        entityType: 'publisher',
689
      });
690
    }
691
    if (typeof topic !== 'string') {
1,155✔
692
      throw new TypeValidationError('topic', topic, 'string', {
12✔
693
        nodeName: this.name(),
694
        entityType: 'publisher',
695
      });
696
    }
697
    if (
1,143!
698
      eventCallbacks &&
1,145✔
699
      !(eventCallbacks instanceof PublisherEventCallbacks)
700
    ) {
UNCOV
701
      throw new TypeValidationError(
×
702
        'eventCallbacks',
703
        eventCallbacks,
704
        'PublisherEventCallbacks',
705
        {
706
          nodeName: this.name(),
707
          entityType: 'publisher',
708
          entityName: topic,
709
        }
710
      );
711
    }
712

713
    let publisher = publisherClass.createPublisher(
1,143✔
714
      this,
715
      typeClass,
716
      topic,
717
      options,
718
      eventCallbacks
719
    );
720
    debug('Finish creating publisher, topic = %s.', topic);
1,133✔
721
    this._publishers.push(publisher);
1,133✔
722
    return publisher;
1,133✔
723
  }
724

725
  /**
726
   * This callback is called when a message is published
727
   * @callback SubscriptionCallback
728
   * @param {Object} message - The message published
729
   * @see [Node.createSubscription]{@link Node#createSubscription}
730
   * @see [Node.createPublisher]{@link Node#createPublisher}
731
   * @see {@link Publisher}
732
   * @see {@link Subscription}
733
   */
734

735
  /**
736
   * Create a Subscription with optional content-filtering.
737
   * @param {function|string|object} typeClass - The ROS message class,
738
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
739
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
740
   * @param {string} topic - The name of the topic.
741
   * @param {object} options - The options argument used to parameterize the subscription.
742
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
743
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the subscription, default: QoS.profileDefault.
744
   * @param {boolean} options.isRaw - The topic is serialized when true, default: false.
745
   * @param {string} [options.serializationMode='default'] - Controls message serialization format:
746
   *  'default': Use native rclnodejs behavior (respects enableTypedArray setting),
747
   *  'plain': Convert TypedArrays to regular arrays,
748
   *  'json': Fully JSON-safe (handles TypedArrays, BigInt, etc.).
749
   * @param {object} [options.contentFilter=undefined] - The content-filter, default: undefined.
750
   *  Confirm that your RMW supports content-filtered topics before use. 
751
   * @param {string} options.contentFilter.expression - Specifies the criteria to select the data samples of
752
   *  interest. It is similar to the WHERE part of an SQL clause.
753
   * @param {string[]} [options.contentFilter.parameters=undefined] - Array of strings that give values to
754
   *  the ‘parameters’ (i.e., "%n" tokens) in the filter_expression. The number of supplied parameters must
755
   *  fit with the requested values in the filter_expression (i.e., the number of %n tokens). default: undefined.
756
   * @param {SubscriptionCallback} callback - The callback to be call when receiving the topic subscribed. The topic will be an instance of null-terminated Buffer when options.isRaw is true.
757
   * @param {SubscriptionEventCallbacks} eventCallbacks - The event callbacks for the subscription.
758
   * @return {Subscription} - An instance of Subscription.
759
   * @throws {ERROR} - May throw an RMW error if content-filter is malformed. 
760
   * @see {@link SubscriptionCallback}
761
   * @see {@link https://www.omg.org/spec/DDS/1.4/PDF|Content-filter details at DDS 1.4 specification, Annex B}
762
   */
763
  createSubscription(typeClass, topic, options, callback, eventCallbacks) {
764
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
436✔
765
      typeClass = loader.loadInterface(typeClass);
427✔
766
    }
767

768
    if (typeof options === 'function') {
429✔
769
      callback = options;
381✔
770
      options = undefined;
381✔
771
    }
772
    options = this._validateOptions(options);
429✔
773

774
    if (typeof typeClass !== 'function') {
419✔
775
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
776
        nodeName: this.name(),
777
        entityType: 'subscription',
778
      });
779
    }
780
    if (typeof topic !== 'string') {
415✔
781
      throw new TypeValidationError('topic', topic, 'string', {
6✔
782
        nodeName: this.name(),
783
        entityType: 'subscription',
784
      });
785
    }
786
    if (typeof callback !== 'function') {
409!
UNCOV
787
      throw new TypeValidationError('callback', callback, 'function', {
×
788
        nodeName: this.name(),
789
        entityType: 'subscription',
790
        entityName: topic,
791
      });
792
    }
793
    if (
409!
794
      eventCallbacks &&
413✔
795
      !(eventCallbacks instanceof SubscriptionEventCallbacks)
796
    ) {
UNCOV
797
      throw new TypeValidationError(
×
798
        'eventCallbacks',
799
        eventCallbacks,
800
        'SubscriptionEventCallbacks',
801
        {
802
          nodeName: this.name(),
803
          entityType: 'subscription',
804
          entityName: topic,
805
        }
806
      );
807
    }
808

809
    let subscription = Subscription.createSubscription(
409✔
810
      this,
811
      typeClass,
812
      topic,
813
      options,
814
      callback,
815
      eventCallbacks
816
    );
817
    debug('Finish creating subscription, topic = %s.', topic);
398✔
818
    this._subscriptions.push(subscription);
398✔
819
    this.syncHandles();
398✔
820

821
    return subscription;
398✔
822
  }
823

824
  /**
825
   * Create a Subscription that returns an RxJS Observable.
826
   * This allows using reactive programming patterns with ROS 2 messages.
827
   *
828
   * @param {function|string|object} typeClass - The ROS message class,
829
   *      OR a string representing the message class, e.g. 'std_msgs/msg/String',
830
   *      OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
831
   * @param {string} topic - The name of the topic.
832
   * @param {object} [options] - The options argument used to parameterize the subscription.
833
   * @param {boolean} [options.enableTypedArray=true] - The topic will use TypedArray if necessary.
834
   * @param {QoS} [options.qos=QoS.profileDefault] - ROS Middleware "quality of service" settings.
835
   * @param {boolean} [options.isRaw=false] - The topic is serialized when true.
836
   * @param {string} [options.serializationMode='default'] - Controls message serialization format.
837
   * @param {object} [options.contentFilter] - The content-filter (if supported by RMW).
838
   * @param {SubscriptionEventCallbacks} [eventCallbacks] - The event callbacks for the subscription.
839
   * @return {ObservableSubscription} - An ObservableSubscription with an RxJS Observable.
840
   */
841
  createObservableSubscription(typeClass, topic, options, eventCallbacks) {
842
    let observableSubscription = null;
7✔
843

844
    const subscription = this.createSubscription(
7✔
845
      typeClass,
846
      topic,
847
      options,
848
      (message) => {
849
        if (observableSubscription) {
8!
850
          observableSubscription._emit(message);
8✔
851
        }
852
      },
853
      eventCallbacks
854
    );
855

856
    observableSubscription = new ObservableSubscription(subscription);
7✔
857
    return observableSubscription;
7✔
858
  }
859

860
  /**
861
   * Create a Client.
862
   * @param {function|string|object} typeClass - The ROS message class,
863
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
864
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
865
   * @param {string} serviceName - The service name to request.
866
   * @param {object} options - The options argument used to parameterize the client.
867
   * @param {boolean} options.enableTypedArray - The response will use TypedArray if necessary, default: true.
868
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the client, default: QoS.profileDefault.
869
   * @return {Client} - An instance of Client.
870
   */
871
  createClient(typeClass, serviceName, options) {
872
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
196✔
873
      typeClass = loader.loadInterface(typeClass);
186✔
874
    }
875
    options = this._validateOptions(options);
189✔
876

877
    if (typeof typeClass !== 'function') {
189✔
878
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
879
        nodeName: this.name(),
880
        entityType: 'client',
881
      });
882
    }
883
    if (typeof serviceName !== 'string') {
181✔
884
      throw new TypeValidationError('serviceName', serviceName, 'string', {
12✔
885
        nodeName: this.name(),
886
        entityType: 'client',
887
      });
888
    }
889

890
    let client = Client.createClient(
169✔
891
      this.handle,
892
      serviceName,
893
      typeClass,
894
      options
895
    );
896
    debug('Finish creating client, service = %s.', serviceName);
159✔
897
    this._clients.push(client);
159✔
898
    this.syncHandles();
159✔
899

900
    return client;
159✔
901
  }
902

903
  /**
904
   * This callback is called when a request is sent to service
905
   * @callback RequestCallback
906
   * @param {Object} request - The request sent to the service
907
   * @param {Response} response - The response to client.
908
        Use [response.send()]{@link Response#send} to send response object to client
909
   * @return {undefined}
910
   * @see [Node.createService]{@link Node#createService}
911
   * @see [Client.sendRequest]{@link Client#sendRequest}
912
   * @see {@link Client}
913
   * @see {@link Service}
914
   * @see {@link Response#send}
915
   */
916

917
  /**
918
   * Create a Service.
919
   * @param {function|string|object} typeClass - The ROS message class,
920
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
921
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
922
   * @param {string} serviceName - The service name to offer.
923
   * @param {object} options - The options argument used to parameterize the service.
924
   * @param {boolean} options.enableTypedArray - The request will use TypedArray if necessary, default: true.
925
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the service, default: QoS.profileDefault.
926
   * @param {RequestCallback} callback - The callback to be called when receiving request.
927
   * @return {Service} - An instance of Service.
928
   * @see {@link RequestCallback}
929
   */
930
  createService(typeClass, serviceName, options, callback) {
931
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
4,825✔
932
      typeClass = loader.loadInterface(typeClass);
4,815✔
933
    }
934

935
    if (typeof options === 'function') {
4,818✔
936
      callback = options;
4,795✔
937
      options = undefined;
4,795✔
938
    }
939
    options = this._validateOptions(options);
4,818✔
940

941
    if (typeof typeClass !== 'function') {
4,808✔
942
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
943
        nodeName: this.name(),
944
        entityType: 'service',
945
      });
946
    }
947
    if (typeof serviceName !== 'string') {
4,804✔
948
      throw new TypeValidationError('serviceName', serviceName, 'string', {
6✔
949
        nodeName: this.name(),
950
        entityType: 'service',
951
      });
952
    }
953
    if (typeof callback !== 'function') {
4,798!
UNCOV
954
      throw new TypeValidationError('callback', callback, 'function', {
×
955
        nodeName: this.name(),
956
        entityType: 'service',
957
        entityName: serviceName,
958
      });
959
    }
960

961
    let service = Service.createService(
4,798✔
962
      this.handle,
963
      serviceName,
964
      typeClass,
965
      options,
966
      callback
967
    );
968
    debug('Finish creating service, service = %s.', serviceName);
4,788✔
969
    this._services.push(service);
4,788✔
970
    this.syncHandles();
4,788✔
971

972
    return service;
4,788✔
973
  }
974

975
  /**
976
   * Create a ParameterClient for accessing parameters on a remote node.
977
   * @param {string} remoteNodeName - The name of the remote node whose parameters to access.
978
   * @param {object} [options] - Options for parameter client.
979
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
980
   * @return {ParameterClient} - An instance of ParameterClient.
981
   */
982
  createParameterClient(remoteNodeName, options = {}) {
50✔
983
    if (typeof remoteNodeName !== 'string' || remoteNodeName.trim() === '') {
103!
UNCOV
984
      throw new TypeError('Remote node name must be a non-empty string');
×
985
    }
986

987
    const parameterClient = new ParameterClient(this, remoteNodeName, options);
103✔
988
    debug(
103✔
989
      'Finish creating parameter client for remote node = %s.',
990
      remoteNodeName
991
    );
992
    this._parameterClients.push(parameterClient);
103✔
993

994
    return parameterClient;
103✔
995
  }
996

997
  /**
998
   * Create a ParameterWatcher for watching parameter changes on a remote node.
999
   * @param {string} remoteNodeName - The name of the remote node whose parameters to watch.
1000
   * @param {string[]} parameterNames - Array of parameter names to watch.
1001
   * @param {object} [options] - Options for parameter watcher.
1002
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
1003
   * @return {ParameterWatcher} - An instance of ParameterWatcher.
1004
   */
1005
  createParameterWatcher(remoteNodeName, parameterNames, options = {}) {
56✔
1006
    const watcher = new ParameterWatcher(
57✔
1007
      this,
1008
      remoteNodeName,
1009
      parameterNames,
1010
      options
1011
    );
1012
    debug(
53✔
1013
      'Finish creating parameter watcher for remote node = %s.',
1014
      remoteNodeName
1015
    );
1016
    this._parameterWatchers.push(watcher);
53✔
1017

1018
    return watcher;
53✔
1019
  }
1020

1021
  /**
1022
   * Create a guard condition.
1023
   * @param {Function} callback - The callback to be called when the guard condition is triggered.
1024
   * @return {GuardCondition} - An instance of GuardCondition.
1025
   */
1026
  createGuardCondition(callback) {
1027
    if (typeof callback !== 'function') {
3!
UNCOV
1028
      throw new TypeValidationError('callback', callback, 'function', {
×
1029
        nodeName: this.name(),
1030
        entityType: 'guard_condition',
1031
      });
1032
    }
1033

1034
    let guard = GuardCondition.createGuardCondition(callback, this.context);
3✔
1035
    debug('Finish creating guard condition');
3✔
1036
    this._guards.push(guard);
3✔
1037
    this.syncHandles();
3✔
1038

1039
    return guard;
3✔
1040
  }
1041

1042
  /**
1043
   * Destroy all resource allocated by this node, including
1044
   * <code>Timer</code>s/<code>Publisher</code>s/<code>Subscription</code>s
1045
   * /<code>Client</code>s/<code>Service</code>s
1046
   * @return {undefined}
1047
   */
1048
  destroy() {
1049
    if (this.spinning) {
820✔
1050
      this.stop();
536✔
1051
    }
1052

1053
    // Action servers/clients require manual destruction due to circular reference with goal handles.
1054
    this._actionClients.forEach((actionClient) => actionClient.destroy());
820✔
1055
    this._actionServers.forEach((actionServer) => actionServer.destroy());
820✔
1056

1057
    this._parameterClients.forEach((paramClient) => paramClient.destroy());
820✔
1058
    this._parameterWatchers.forEach((watcher) => watcher.destroy());
820✔
1059

1060
    this.context.onNodeDestroyed(this);
820✔
1061

1062
    if (this._enableRosout) {
820✔
1063
      rclnodejs.finiRosoutPublisherForNode(this.handle);
797✔
1064
      this._enableRosout = false;
797✔
1065
    }
1066

1067
    this.handle.release();
820✔
1068
    this._clock = null;
820✔
1069
    this._timers = [];
820✔
1070
    this._publishers = [];
820✔
1071
    this._subscriptions = [];
820✔
1072
    this._clients = [];
820✔
1073
    this._services = [];
820✔
1074
    this._guards = [];
820✔
1075
    this._actionClients = [];
820✔
1076
    this._actionServers = [];
820✔
1077
    this._parameterClients = [];
820✔
1078
    this._parameterWatchers = [];
820✔
1079

1080
    if (this._rateTimerServer) {
820✔
1081
      this._rateTimerServer.shutdown();
5✔
1082
      this._rateTimerServer = null;
5✔
1083
    }
1084
  }
1085

1086
  /**
1087
   * Destroy a Publisher.
1088
   * @param {Publisher} publisher - The Publisher to be destroyed.
1089
   * @return {undefined}
1090
   */
1091
  destroyPublisher(publisher) {
1092
    if (!(publisher instanceof Publisher)) {
9✔
1093
      throw new TypeValidationError(
2✔
1094
        'publisher',
1095
        publisher,
1096
        'Publisher instance',
1097
        {
1098
          nodeName: this.name(),
1099
        }
1100
      );
1101
    }
1102
    if (publisher.events) {
7!
UNCOV
1103
      publisher.events.forEach((event) => {
×
UNCOV
1104
        this._destroyEntity(event, this._events);
×
1105
      });
UNCOV
1106
      publisher.events = [];
×
1107
    }
1108
    this._destroyEntity(publisher, this._publishers, false);
7✔
1109
  }
1110

1111
  /**
1112
   * Destroy a Subscription.
1113
   * @param {Subscription} subscription - The Subscription to be destroyed.
1114
   * @return {undefined}
1115
   */
1116
  destroySubscription(subscription) {
1117
    if (!(subscription instanceof Subscription)) {
82✔
1118
      throw new TypeValidationError(
2✔
1119
        'subscription',
1120
        subscription,
1121
        'Subscription instance',
1122
        {
1123
          nodeName: this.name(),
1124
        }
1125
      );
1126
    }
1127
    if (subscription.events) {
80✔
1128
      subscription.events.forEach((event) => {
1✔
1129
        this._destroyEntity(event, this._events);
1✔
1130
      });
1131
      subscription.events = [];
1✔
1132
    }
1133

1134
    this._destroyEntity(subscription, this._subscriptions);
80✔
1135
  }
1136

1137
  /**
1138
   * Destroy a Client.
1139
   * @param {Client} client - The Client to be destroyed.
1140
   * @return {undefined}
1141
   */
1142
  destroyClient(client) {
1143
    if (!(client instanceof Client)) {
117✔
1144
      throw new TypeValidationError('client', client, 'Client instance', {
2✔
1145
        nodeName: this.name(),
1146
      });
1147
    }
1148
    this._destroyEntity(client, this._clients);
115✔
1149
  }
1150

1151
  /**
1152
   * Destroy a Service.
1153
   * @param {Service} service - The Service to be destroyed.
1154
   * @return {undefined}
1155
   */
1156
  destroyService(service) {
1157
    if (!(service instanceof Service)) {
8✔
1158
      throw new TypeValidationError('service', service, 'Service instance', {
2✔
1159
        nodeName: this.name(),
1160
      });
1161
    }
1162
    this._destroyEntity(service, this._services);
6✔
1163
  }
1164

1165
  /**
1166
   * Destroy a ParameterClient.
1167
   * @param {ParameterClient} parameterClient - The ParameterClient to be destroyed.
1168
   * @return {undefined}
1169
   */
1170
  destroyParameterClient(parameterClient) {
1171
    if (!(parameterClient instanceof ParameterClient)) {
54!
UNCOV
1172
      throw new TypeError('Invalid argument');
×
1173
    }
1174
    this._removeEntityFromArray(parameterClient, this._parameterClients);
54✔
1175
    parameterClient.destroy();
54✔
1176
  }
1177

1178
  /**
1179
   * Destroy a ParameterWatcher.
1180
   * @param {ParameterWatcher} watcher - The ParameterWatcher to be destroyed.
1181
   * @return {undefined}
1182
   */
1183
  destroyParameterWatcher(watcher) {
1184
    if (!(watcher instanceof ParameterWatcher)) {
1!
UNCOV
1185
      throw new TypeError('Invalid argument');
×
1186
    }
1187
    this._removeEntityFromArray(watcher, this._parameterWatchers);
1✔
1188
    watcher.destroy();
1✔
1189
  }
1190

1191
  /**
1192
   * Destroy a Timer.
1193
   * @param {Timer} timer - The Timer to be destroyed.
1194
   * @return {undefined}
1195
   */
1196
  destroyTimer(timer) {
1197
    if (!(timer instanceof Timer)) {
8✔
1198
      throw new TypeValidationError('timer', timer, 'Timer instance', {
2✔
1199
        nodeName: this.name(),
1200
      });
1201
    }
1202
    this._destroyEntity(timer, this._timers);
6✔
1203
  }
1204

1205
  /**
1206
   * Destroy a guard condition.
1207
   * @param {GuardCondition} guard - The guard condition to be destroyed.
1208
   * @return {undefined}
1209
   */
1210
  destroyGuardCondition(guard) {
1211
    if (!(guard instanceof GuardCondition)) {
3!
UNCOV
1212
      throw new TypeValidationError('guard', guard, 'GuardCondition instance', {
×
1213
        nodeName: this.name(),
1214
      });
1215
    }
1216
    this._destroyEntity(guard, this._guards);
3✔
1217
  }
1218

1219
  /**
1220
   * Get the name of the node.
1221
   * @return {string}
1222
   */
1223
  name() {
1224
    return rclnodejs.getNodeName(this.handle);
4,719✔
1225
  }
1226

1227
  /**
1228
   * Get the namespace of the node.
1229
   * @return {string}
1230
   */
1231
  namespace() {
1232
    return rclnodejs.getNamespace(this.handle);
4,442✔
1233
  }
1234

1235
  /**
1236
   * Get the context in which this node was created.
1237
   * @return {Context}
1238
   */
1239
  get context() {
1240
    return this._context;
6,105✔
1241
  }
1242

1243
  /**
1244
   * Get the nodes logger.
1245
   * @returns {Logger} - The logger for the node.
1246
   */
1247
  getLogger() {
1248
    return this._logger;
141✔
1249
  }
1250

1251
  /**
1252
   * Get the clock used by the node.
1253
   * @returns {Clock} - The nodes clock.
1254
   */
1255
  getClock() {
1256
    return this._clock;
86✔
1257
  }
1258

1259
  /**
1260
   * Get the current time using the node's clock.
1261
   * @returns {Timer} - The current time.
1262
   */
1263
  now() {
1264
    return this.getClock().now();
2✔
1265
  }
1266

1267
  /**
1268
   * Get the list of published topics discovered by the provided node for the remote node name.
1269
   * @param {string} nodeName - The name of the node.
1270
   * @param {string} namespace - The name of the namespace.
1271
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1272
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1273
   */
1274
  getPublisherNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
2✔
1275
    return rclnodejs.getPublisherNamesAndTypesByNode(
2✔
1276
      this.handle,
1277
      nodeName,
1278
      namespace,
1279
      noDemangle
1280
    );
1281
  }
1282

1283
  /**
1284
   * Get the list of published topics discovered by the provided node for the remote node name.
1285
   * @param {string} nodeName - The name of the node.
1286
   * @param {string} namespace - The name of the namespace.
1287
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1288
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1289
   */
1290
  getSubscriptionNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
×
UNCOV
1291
    return rclnodejs.getSubscriptionNamesAndTypesByNode(
×
1292
      this.handle,
1293
      nodeName,
1294
      namespace,
1295
      noDemangle
1296
    );
1297
  }
1298

1299
  /**
1300
   * Get service names and types for which a remote node has servers.
1301
   * @param {string} nodeName - The name of the node.
1302
   * @param {string} namespace - The name of the namespace.
1303
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1304
   */
1305
  getServiceNamesAndTypesByNode(nodeName, namespace) {
UNCOV
1306
    return rclnodejs.getServiceNamesAndTypesByNode(
×
1307
      this.handle,
1308
      nodeName,
1309
      namespace
1310
    );
1311
  }
1312

1313
  /**
1314
   * Get service names and types for which a remote node has clients.
1315
   * @param {string} nodeName - The name of the node.
1316
   * @param {string} namespace - The name of the namespace.
1317
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1318
   */
1319
  getClientNamesAndTypesByNode(nodeName, namespace) {
UNCOV
1320
    return rclnodejs.getClientNamesAndTypesByNode(
×
1321
      this.handle,
1322
      nodeName,
1323
      namespace
1324
    );
1325
  }
1326

1327
  /**
1328
   * Get the list of topics discovered by the provided node.
1329
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1330
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1331
   */
1332
  getTopicNamesAndTypes(noDemangle = false) {
×
UNCOV
1333
    return rclnodejs.getTopicNamesAndTypes(this.handle, noDemangle);
×
1334
  }
1335

1336
  /**
1337
   * Get the list of services discovered by the provided node.
1338
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1339
   */
1340
  getServiceNamesAndTypes() {
1341
    return rclnodejs.getServiceNamesAndTypes(this.handle);
2✔
1342
  }
1343

1344
  /**
1345
   * Return a list of publishers on a given topic.
1346
   *
1347
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
1348
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
1349
   *
1350
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
1351
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1352
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
1353
   * follow ROS topic name conventions.
1354
   *
1355
   * `topic` may be a relative, private, or fully qualified topic name.
1356
   *  A relative or private topic will be expanded using this node's namespace and name.
1357
   *  The queried `topic` is not remapped.
1358
   *
1359
   * @param {string} topic - The topic on which to find the publishers.
1360
   * @param {boolean} [noDemangle=false] - If `true`, `topic` needs to be a valid middleware topic
1361
   *                               name, otherwise it should be a valid ROS topic name. Defaults to `false`.
1362
   * @returns {Array} - list of publishers
1363
   */
1364
  getPublishersInfoByTopic(topic, noDemangle = false) {
1✔
1365
    return rclnodejs.getPublishersInfoByTopic(
4✔
1366
      this.handle,
1367
      this._getValidatedTopic(topic, noDemangle),
1368
      noDemangle
1369
    );
1370
  }
1371

1372
  /**
1373
   * Return a list of subscriptions on a given topic.
1374
   *
1375
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
1376
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
1377
   *
1378
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
1379
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1380
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
1381
   * follow ROS topic name conventions.
1382
   *
1383
   * `topic` may be a relative, private, or fully qualified topic name.
1384
   *  A relative or private topic will be expanded using this node's namespace and name.
1385
   *  The queried `topic` is not remapped.
1386
   *
1387
   * @param {string} topic - The topic on which to find the subscriptions.
1388
   * @param {boolean} [noDemangle=false] -  If `true`, `topic` needs to be a valid middleware topic
1389
                                    name, otherwise it should be a valid ROS topic name. Defaults to `false`.
1390
   * @returns {Array} - list of subscriptions
1391
   */
1392
  getSubscriptionsInfoByTopic(topic, noDemangle = false) {
×
1393
    return rclnodejs.getSubscriptionsInfoByTopic(
2✔
1394
      this.handle,
1395
      this._getValidatedTopic(topic, noDemangle),
1396
      noDemangle
1397
    );
1398
  }
1399

1400
  /**
1401
   * Return a list of clients on a given service.
1402
   *
1403
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
1404
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
1405
   *
1406
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
1407
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1408
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
1409
   * follow ROS service name conventions.
1410
   *
1411
   * `service` may be a relative, private, or fully qualified service name.
1412
   *  A relative or private service will be expanded using this node's namespace and name.
1413
   *  The queried `service` is not remapped.
1414
   *
1415
   * @param {string} service - The service on which to find the clients.
1416
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
1417
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
1418
   * @returns {Array} - list of clients
1419
   */
1420
  getClientsInfoByService(service, noDemangle = false) {
×
1421
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.ROLLING) {
2!
UNCOV
1422
      console.warn(
×
1423
        'getClientsInfoByService is not supported by this version of ROS 2'
1424
      );
UNCOV
1425
      return null;
×
1426
    }
1427
    return rclnodejs.getClientsInfoByService(
2✔
1428
      this.handle,
1429
      this._getValidatedServiceName(service, noDemangle),
1430
      noDemangle
1431
    );
1432
  }
1433

1434
  /**
1435
   * Return a list of servers on a given service.
1436
   *
1437
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
1438
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
1439
   *
1440
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
1441
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1442
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
1443
   * follow ROS service name conventions.
1444
   *
1445
   * `service` may be a relative, private, or fully qualified service name.
1446
   *  A relative or private service will be expanded using this node's namespace and name.
1447
   *  The queried `service` is not remapped.
1448
   *
1449
   * @param {string} service - The service on which to find the servers.
1450
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
1451
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
1452
   * @returns {Array} - list of servers
1453
   */
1454
  getServersInfoByService(service, noDemangle = false) {
×
1455
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.ROLLING) {
2!
UNCOV
1456
      console.warn(
×
1457
        'getServersInfoByService is not supported by this version of ROS 2'
1458
      );
UNCOV
1459
      return null;
×
1460
    }
1461
    return rclnodejs.getServersInfoByService(
2✔
1462
      this.handle,
1463
      this._getValidatedServiceName(service, noDemangle),
1464
      noDemangle
1465
    );
1466
  }
1467

1468
  /**
1469
   * Get the list of nodes discovered by the provided node.
1470
   * @return {Array<string>} - An array of the names.
1471
   */
1472
  getNodeNames() {
1473
    return this.getNodeNamesAndNamespaces().map((item) => item.name);
41✔
1474
  }
1475

1476
  /**
1477
   * Get the list of nodes and their namespaces discovered by the provided node.
1478
   * @return {Array<{name: string, namespace: string}>} An array of the names and namespaces.
1479
   */
1480
  getNodeNamesAndNamespaces() {
1481
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ false);
17✔
1482
  }
1483

1484
  /**
1485
   * Get the list of nodes and their namespaces with enclaves discovered by the provided node.
1486
   * @return {Array<{name: string, namespace: string, enclave: string}>} An array of the names, namespaces and enclaves.
1487
   */
1488
  getNodeNamesAndNamespacesWithEnclaves() {
1489
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ true);
1✔
1490
  }
1491

1492
  /**
1493
   * Return the number of publishers on a given topic.
1494
   * @param {string} topic - The name of the topic.
1495
   * @returns {number} - Number of publishers on the given topic.
1496
   */
1497
  countPublishers(topic) {
1498
    let expandedTopic = rclnodejs.expandTopicName(
6✔
1499
      topic,
1500
      this.name(),
1501
      this.namespace()
1502
    );
1503
    rclnodejs.validateTopicName(expandedTopic);
6✔
1504

1505
    return rclnodejs.countPublishers(this.handle, expandedTopic);
6✔
1506
  }
1507

1508
  /**
1509
   * Return the number of subscribers on a given topic.
1510
   * @param {string} topic - The name of the topic.
1511
   * @returns {number} - Number of subscribers on the given topic.
1512
   */
1513
  countSubscribers(topic) {
1514
    let expandedTopic = rclnodejs.expandTopicName(
6✔
1515
      topic,
1516
      this.name(),
1517
      this.namespace()
1518
    );
1519
    rclnodejs.validateTopicName(expandedTopic);
6✔
1520

1521
    return rclnodejs.countSubscribers(this.handle, expandedTopic);
6✔
1522
  }
1523

1524
  /**
1525
   * Get the number of clients on a given service name.
1526
   * @param {string} serviceName - the service name
1527
   * @returns {Number}
1528
   */
1529
  countClients(serviceName) {
1530
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
2!
UNCOV
1531
      console.warn('countClients is not supported by this version of ROS 2');
×
UNCOV
1532
      return null;
×
1533
    }
1534
    return rclnodejs.countClients(this.handle, serviceName);
2✔
1535
  }
1536

1537
  /**
1538
   * Get the number of services on a given service name.
1539
   * @param {string} serviceName - the service name
1540
   * @returns {Number}
1541
   */
1542
  countServices(serviceName) {
1543
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
1!
UNCOV
1544
      console.warn('countServices is not supported by this version of ROS 2');
×
UNCOV
1545
      return null;
×
1546
    }
1547
    return rclnodejs.countServices(this.handle, serviceName);
1✔
1548
  }
1549

1550
  /**
1551
   * Get the list of parameter-overrides found on the commandline and
1552
   * in the NodeOptions.parameter_overrides property.
1553
   *
1554
   * @return {Array<Parameter>} - An array of Parameters.
1555
   */
1556
  getParameterOverrides() {
1557
    return Array.from(this._parameterOverrides.values());
8✔
1558
  }
1559

1560
  /**
1561
   * Declare a parameter.
1562
   *
1563
   * Internally, register a parameter and it's descriptor.
1564
   * If a parameter-override exists, it's value will replace that of the parameter
1565
   * unless ignoreOverride is true.
1566
   * If the descriptor is undefined, then a ParameterDescriptor will be inferred
1567
   * from the parameter's state.
1568
   *
1569
   * If a parameter by the same name has already been declared then an Error is thrown.
1570
   * A parameter must be undeclared before attempting to redeclare it.
1571
   *
1572
   * @param {Parameter} parameter - Parameter to declare.
1573
   * @param {ParameterDescriptor} [descriptor] - Optional descriptor for parameter.
1574
   * @param {boolean} [ignoreOverride] - When true disregard any parameter-override that may be present.
1575
   * @return {Parameter} - The newly declared parameter.
1576
   */
1577
  declareParameter(parameter, descriptor, ignoreOverride = false) {
2,178✔
1578
    const parameters = this.declareParameters(
2,179✔
1579
      [parameter],
1580
      descriptor ? [descriptor] : [],
2,179✔
1581
      ignoreOverride
1582
    );
1583
    return parameters.length == 1 ? parameters[0] : null;
2,179!
1584
  }
1585

1586
  /**
1587
   * Declare a list of parameters.
1588
   *
1589
   * Internally register parameters with their corresponding descriptor one by one
1590
   * in the order they are provided. This is an atomic operation. If an error
1591
   * occurs the process halts and no further parameters are declared.
1592
   * Parameters that have already been processed are undeclared.
1593
   *
1594
   * While descriptors is an optional parameter, when provided there must be
1595
   * a descriptor for each parameter; otherwise an Error is thrown.
1596
   * If descriptors is not provided then a descriptor will be inferred
1597
   * from each parameter's state.
1598
   *
1599
   * When a parameter-override is available, the parameter's value
1600
   * will be replaced with that of the parameter-override unless ignoreOverrides
1601
   * is true.
1602
   *
1603
   * If a parameter by the same name has already been declared then an Error is thrown.
1604
   * A parameter must be undeclared before attempting to redeclare it.
1605
   *
1606
   * Prior to declaring the parameters each SetParameterEventCallback registered
1607
   * using setOnParameterEventCallback() is called in succession with the parameters
1608
   * list. Any SetParameterEventCallback that retuns does not return a successful
1609
   * result will cause the entire operation to terminate with no changes to the
1610
   * parameters. When all SetParameterEventCallbacks return successful then the
1611
   * list of parameters is updated.
1612
   *
1613
   * @param {Parameter[]} parameters - The parameters to declare.
1614
   * @param {ParameterDescriptor[]} [descriptors] - Optional descriptors,
1615
   *    a 1-1 correspondence with parameters.
1616
   * @param {boolean} ignoreOverrides - When true, parameter-overrides are
1617
   *    not considered, i.e.,ignored.
1618
   * @return {Parameter[]} - The declared parameters.
1619
   */
1620
  declareParameters(parameters, descriptors = [], ignoreOverrides = false) {
×
1621
    if (!Array.isArray(parameters)) {
2,179!
UNCOV
1622
      throw new TypeValidationError('parameters', parameters, 'Array', {
×
1623
        nodeName: this.name(),
1624
      });
1625
    }
1626
    if (!Array.isArray(descriptors)) {
2,179!
UNCOV
1627
      throw new TypeValidationError('descriptors', descriptors, 'Array', {
×
1628
        nodeName: this.name(),
1629
      });
1630
    }
1631
    if (descriptors.length > 0 && parameters.length !== descriptors.length) {
2,179!
UNCOV
1632
      throw new ValidationError(
×
1633
        'Each parameter must have a corresponding ParameterDescriptor',
1634
        {
1635
          code: 'PARAMETER_DESCRIPTOR_MISMATCH',
1636
          argumentName: 'descriptors',
1637
          providedValue: descriptors.length,
1638
          expectedType: `Array with length ${parameters.length}`,
1639
          nodeName: this.name(),
1640
        }
1641
      );
1642
    }
1643

1644
    const declaredDescriptors = [];
2,179✔
1645
    const declaredParameters = [];
2,179✔
1646
    const declaredParameterCollisions = [];
2,179✔
1647
    for (let i = 0; i < parameters.length; i++) {
2,179✔
1648
      let parameter =
1649
        !ignoreOverrides && this._parameterOverrides.has(parameters[i].name)
2,179✔
1650
          ? this._parameterOverrides.get(parameters[i].name)
1651
          : parameters[i];
1652

1653
      // stop processing parameters that have already been declared
1654
      if (this._parameters.has(parameter.name)) {
2,179!
UNCOV
1655
        declaredParameterCollisions.push(parameter);
×
UNCOV
1656
        continue;
×
1657
      }
1658

1659
      // create descriptor for parameter if not provided
1660
      let descriptor =
1661
        descriptors.length > 0
2,179✔
1662
          ? descriptors[i]
1663
          : ParameterDescriptor.fromParameter(parameter);
1664

1665
      descriptor.validate();
2,179✔
1666

1667
      declaredDescriptors.push(descriptor);
2,179✔
1668
      declaredParameters.push(parameter);
2,179✔
1669
    }
1670

1671
    if (declaredParameterCollisions.length > 0) {
2,179!
1672
      const errorMsg =
UNCOV
1673
        declaredParameterCollisions.length == 1
×
1674
          ? `Parameter(${declaredParameterCollisions[0]}) already declared.`
1675
          : `Multiple parameters already declared, e.g., Parameter(${declaredParameterCollisions[0]}).`;
UNCOV
1676
      throw new Error(errorMsg);
×
1677
    }
1678

1679
    // register descriptor
1680
    for (const descriptor of declaredDescriptors) {
2,179✔
1681
      this._parameterDescriptors.set(descriptor.name, descriptor);
2,179✔
1682
    }
1683

1684
    const result = this._setParametersAtomically(declaredParameters, true);
2,179✔
1685
    if (!result.successful) {
2,179!
1686
      // unregister descriptors
UNCOV
1687
      for (const descriptor of declaredDescriptors) {
×
UNCOV
1688
        this._parameterDescriptors.delete(descriptor.name);
×
1689
      }
1690

UNCOV
1691
      throw new Error(result.reason);
×
1692
    }
1693

1694
    return this.getParameters(declaredParameters.map((param) => param.name));
2,179✔
1695
  }
1696

1697
  /**
1698
   * Undeclare a parameter.
1699
   *
1700
   * Readonly parameters can not be undeclared or updated.
1701
   * @param {string} name - Name of parameter to undeclare.
1702
   * @return {undefined} -
1703
   */
1704
  undeclareParameter(name) {
1705
    if (!this.hasParameter(name)) return;
1!
1706

1707
    const descriptor = this.getParameterDescriptor(name);
1✔
1708
    if (descriptor.readOnly) {
1!
UNCOV
1709
      throw new Error(
×
1710
        `${name} parameter is read-only and can not be undeclared`
1711
      );
1712
    }
1713

1714
    this._parameters.delete(name);
1✔
1715
    this._parameterDescriptors.delete(name);
1✔
1716
  }
1717

1718
  /**
1719
   * Determine if a parameter has been declared.
1720
   * @param {string} name - name of parameter
1721
   * @returns {boolean} - Return true if parameter is declared; false otherwise.
1722
   */
1723
  hasParameter(name) {
1724
    return this._parameters.has(name);
5,427✔
1725
  }
1726

1727
  /**
1728
   * Get a declared parameter by name.
1729
   *
1730
   * If unable to locate a declared parameter then a
1731
   * parameter with type == PARAMETER_NOT_SET is returned.
1732
   *
1733
   * @param {string} name - The name of the parameter.
1734
   * @return {Parameter} - The parameter.
1735
   */
1736
  getParameter(name) {
1737
    return this.getParameters([name])[0];
1,609✔
1738
  }
1739

1740
  /**
1741
   * Get a list of parameters.
1742
   *
1743
   * Find and return the declared parameters.
1744
   * If no names are provided return all declared parameters.
1745
   *
1746
   * If unable to locate a declared parameter then a
1747
   * parameter with type == PARAMETER_NOT_SET is returned in
1748
   * it's place.
1749
   *
1750
   * @param {string[]} [names] - The names of the declared parameters
1751
   *    to find or null indicating to return all declared parameters.
1752
   * @return {Parameter[]} - The parameters.
1753
   */
1754
  getParameters(names = []) {
12✔
1755
    let params = [];
3,826✔
1756

1757
    if (names.length == 0) {
3,826✔
1758
      // get all parameters
1759
      params = [...this._parameters.values()];
12✔
1760
      return params;
12✔
1761
    }
1762

1763
    for (const name of names) {
3,814✔
1764
      const param = this.hasParameter(name)
3,821✔
1765
        ? this._parameters.get(name)
1766
        : new Parameter(name, ParameterType.PARAMETER_NOT_SET);
1767

1768
      params.push(param);
3,821✔
1769
    }
1770

1771
    return params;
3,814✔
1772
  }
1773

1774
  /**
1775
   * Get the types of given parameters.
1776
   *
1777
   * Return the types of given parameters.
1778
   *
1779
   * @param {string[]} [names] - The names of the declared parameters.
1780
   * @return {Uint8Array} - The types.
1781
   */
1782
  getParameterTypes(names = []) {
×
1783
    let types = [];
3✔
1784

1785
    for (const name of names) {
3✔
1786
      const descriptor = this._parameterDescriptors.get(name);
7✔
1787
      if (descriptor) {
7!
1788
        types.push(descriptor.type);
7✔
1789
      }
1790
    }
1791
    return types;
3✔
1792
  }
1793

1794
  /**
1795
   * Get the names of all declared parameters.
1796
   *
1797
   * @return {Array<string>} - The declared parameter names or empty array if
1798
   *    no parameters have been declared.
1799
   */
1800
  getParameterNames() {
1801
    return this.getParameters().map((param) => param.name);
53✔
1802
  }
1803

1804
  /**
1805
   * Determine if a parameter descriptor exists.
1806
   *
1807
   * @param {string} name - The name of a descriptor to for.
1808
   * @return {boolean} - true if a descriptor has been declared; otherwise false.
1809
   */
1810
  hasParameterDescriptor(name) {
1811
    return !!this.getParameterDescriptor(name);
2,204✔
1812
  }
1813

1814
  /**
1815
   * Get a declared parameter descriptor by name.
1816
   *
1817
   * If unable to locate a declared parameter descriptor then a
1818
   * descriptor with type == PARAMETER_NOT_SET is returned.
1819
   *
1820
   * @param {string} name - The name of the parameter descriptor to find.
1821
   * @return {ParameterDescriptor} - The parameter descriptor.
1822
   */
1823
  getParameterDescriptor(name) {
1824
    return this.getParameterDescriptors([name])[0];
4,409✔
1825
  }
1826

1827
  /**
1828
   * Find a list of declared ParameterDescriptors.
1829
   *
1830
   * If no names are provided return all declared descriptors.
1831
   *
1832
   * If unable to locate a declared descriptor then a
1833
   * descriptor with type == PARAMETER_NOT_SET is returned in
1834
   * it's place.
1835
   *
1836
   * @param {string[]} [names] - The names of the declared parameter
1837
   *    descriptors to find or null indicating to return all declared descriptors.
1838
   * @return {ParameterDescriptor[]} - The parameter descriptors.
1839
   */
1840
  getParameterDescriptors(names = []) {
×
1841
    let descriptors = [];
4,412✔
1842

1843
    if (names.length == 0) {
4,412!
1844
      // get all parameters
UNCOV
1845
      descriptors = [...this._parameterDescriptors.values()];
×
UNCOV
1846
      return descriptors;
×
1847
    }
1848

1849
    for (const name of names) {
4,412✔
1850
      let descriptor = this._parameterDescriptors.get(name);
4,414✔
1851
      if (!descriptor) {
4,414!
UNCOV
1852
        descriptor = new ParameterDescriptor(
×
1853
          name,
1854
          ParameterType.PARAMETER_NOT_SET
1855
        );
1856
      }
1857
      descriptors.push(descriptor);
4,414✔
1858
    }
1859

1860
    return descriptors;
4,412✔
1861
  }
1862

1863
  /**
1864
   * Replace a declared parameter.
1865
   *
1866
   * The parameter being replaced must be a declared parameter who's descriptor
1867
   * is not readOnly; otherwise an Error is thrown.
1868
   *
1869
   * @param {Parameter} parameter - The new parameter.
1870
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - The result of the operation.
1871
   */
1872
  setParameter(parameter) {
1873
    const results = this.setParameters([parameter]);
10✔
1874
    return results[0];
10✔
1875
  }
1876

1877
  /**
1878
   * Replace a list of declared parameters.
1879
   *
1880
   * Declared parameters are replaced in the order they are provided and
1881
   * a ParameterEvent is published for each individual parameter change.
1882
   *
1883
   * Prior to setting the parameters each SetParameterEventCallback registered
1884
   * using setOnParameterEventCallback() is called in succession with the parameters
1885
   * list. Any SetParameterEventCallback that retuns does not return a successful
1886
   * result will cause the entire operation to terminate with no changes to the
1887
   * parameters. When all SetParameterEventCallbacks return successful then the
1888
   * list of parameters is updated.
1889
   *
1890
   * If an error occurs, the process is stopped and returned. Parameters
1891
   * set before an error remain unchanged.
1892
   *
1893
   * @param {Parameter[]} parameters - The parameters to set.
1894
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult[]} - A list of SetParameterResult, one for each parameter that was set.
1895
   */
1896
  setParameters(parameters = []) {
×
1897
    return parameters.map((parameter) =>
21✔
1898
      this.setParametersAtomically([parameter])
24✔
1899
    );
1900
  }
1901

1902
  /**
1903
   * Repalce a list of declared parameters atomically.
1904
   *
1905
   * Declared parameters are replaced in the order they are provided.
1906
   * A single ParameterEvent is published collectively for all changed
1907
   * parameters.
1908
   *
1909
   * Prior to setting the parameters each SetParameterEventCallback registered
1910
   * using setOnParameterEventCallback() is called in succession with the parameters
1911
   * list. Any SetParameterEventCallback that retuns does not return a successful
1912
   * result will cause the entire operation to terminate with no changes to the
1913
   * parameters. When all SetParameterEventCallbacks return successful then the
1914
   * list of parameters is updated.d
1915
   *
1916
   * If an error occurs, the process stops immediately. All parameters updated to
1917
   * the point of the error are reverted to their previous state.
1918
   *
1919
   * @param {Parameter[]} parameters - The parameters to set.
1920
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - describes the result of setting 1 or more parameters.
1921
   */
1922
  setParametersAtomically(parameters = []) {
×
1923
    return this._setParametersAtomically(parameters);
25✔
1924
  }
1925

1926
  /**
1927
   * Internal method for updating parameters atomically.
1928
   *
1929
   * Prior to setting the parameters each SetParameterEventCallback registered
1930
   * using setOnParameterEventCallback() is called in succession with the parameters
1931
   * list. Any SetParameterEventCallback that retuns does not return a successful
1932
   * result will cause the entire operation to terminate with no changes to the
1933
   * parameters. When all SetParameterEventCallbacks return successful then the
1934
   * list of parameters is updated.
1935
   *
1936
   * @param {Paramerter[]} parameters - The parameters to update.
1937
   * @param {boolean} declareParameterMode - When true parameters are being declared;
1938
   *    otherwise they are being changed.
1939
   * @return {SetParameterResult} - A single collective result.
1940
   */
1941
  _setParametersAtomically(parameters = [], declareParameterMode = false) {
25!
1942
    let result = this._validateParameters(parameters, declareParameterMode);
2,204✔
1943
    if (!result.successful) {
2,204!
UNCOV
1944
      return result;
×
1945
    }
1946

1947
    // give all SetParametersCallbacks a chance to veto this change
1948
    for (const callback of this._setParametersCallbacks) {
2,204✔
1949
      result = callback(parameters);
1,412✔
1950
      if (!result.successful) {
1,412✔
1951
        // a callback has vetoed a parameter change
1952
        return result;
1✔
1953
      }
1954
    }
1955

1956
    // collectively track updates to parameters for use
1957
    // when publishing a ParameterEvent
1958
    const newParameters = [];
2,203✔
1959
    const changedParameters = [];
2,203✔
1960
    const deletedParameters = [];
2,203✔
1961

1962
    for (const parameter of parameters) {
2,203✔
1963
      if (parameter.type == ParameterType.PARAMETER_NOT_SET) {
2,203✔
1964
        this.undeclareParameter(parameter.name);
1✔
1965
        deletedParameters.push(parameter);
1✔
1966
      } else {
1967
        this._parameters.set(parameter.name, parameter);
2,202✔
1968
        if (declareParameterMode) {
2,202✔
1969
          newParameters.push(parameter);
2,179✔
1970
        } else {
1971
          changedParameters.push(parameter);
23✔
1972
        }
1973
      }
1974
    }
1975

1976
    // create ParameterEvent
1977
    const parameterEvent = new (loader.loadInterface(
2,203✔
1978
      PARAMETER_EVENT_MSG_TYPE
1979
    ))();
1980

1981
    const { seconds, nanoseconds } = this._clock.now().secondsAndNanoseconds;
2,203✔
1982
    parameterEvent.stamp = {
2,203✔
1983
      sec: Number(seconds),
1984
      nanosec: Number(nanoseconds),
1985
    };
1986

1987
    parameterEvent.node =
2,203✔
1988
      this.namespace() === '/'
2,203✔
1989
        ? this.namespace() + this.name()
1990
        : this.namespace() + '/' + this.name();
1991

1992
    if (newParameters.length > 0) {
2,203✔
1993
      parameterEvent['new_parameters'] = newParameters.map((parameter) =>
2,179✔
1994
        parameter.toParameterMessage()
2,179✔
1995
      );
1996
    }
1997
    if (changedParameters.length > 0) {
2,203✔
1998
      parameterEvent['changed_parameters'] = changedParameters.map(
23✔
1999
        (parameter) => parameter.toParameterMessage()
23✔
2000
      );
2001
    }
2002
    if (deletedParameters.length > 0) {
2,203✔
2003
      parameterEvent['deleted_parameters'] = deletedParameters.map(
1✔
2004
        (parameter) => parameter.toParameterMessage()
1✔
2005
      );
2006
    }
2007

2008
    // Publish ParameterEvent.
2009
    this._parameterEventPublisher.publish(parameterEvent);
2,203✔
2010

2011
    return {
2,203✔
2012
      successful: true,
2013
      reason: '',
2014
    };
2015
  }
2016

2017
  /**
2018
   * This callback is called when declaring a parameter or setting a parameter.
2019
   * The callback is provided a list of parameters and returns a SetParameterResult
2020
   * to indicate approval or veto of the operation.
2021
   *
2022
   * @callback SetParametersCallback
2023
   * @param {Parameter[]} parameters - The message published
2024
   * @returns {rcl_interfaces.msg.SetParameterResult} -
2025
   *
2026
   * @see [Node.addOnSetParametersCallback]{@link Node#addOnSetParametersCallback}
2027
   * @see [Node.removeOnSetParametersCallback]{@link Node#removeOnSetParametersCallback}
2028
   */
2029

2030
  /**
2031
   * Add a callback to the front of the list of callbacks invoked for parameter declaration
2032
   * and setting. No checks are made for duplicate callbacks.
2033
   *
2034
   * @param {SetParametersCallback} callback - The callback to add.
2035
   * @returns {undefined}
2036
   */
2037
  addOnSetParametersCallback(callback) {
2038
    this._setParametersCallbacks.unshift(callback);
807✔
2039
  }
2040

2041
  /**
2042
   * Remove a callback from the list of SetParametersCallbacks.
2043
   * If the callback is not found the process is a nop.
2044
   *
2045
   * @param {SetParametersCallback} callback - The callback to be removed
2046
   * @returns {undefined}
2047
   */
2048
  removeOnSetParametersCallback(callback) {
2049
    const idx = this._setParametersCallbacks.indexOf(callback);
2✔
2050
    if (idx > -1) {
2!
2051
      this._setParametersCallbacks.splice(idx, 1);
2✔
2052
    }
2053
  }
2054

2055
  /**
2056
   * Get the fully qualified name of the node.
2057
   *
2058
   * @returns {string} - String containing the fully qualified name of the node.
2059
   */
2060
  getFullyQualifiedName() {
2061
    return rclnodejs.getFullyQualifiedName(this.handle);
1✔
2062
  }
2063

2064
  /**
2065
   * Get the RMW implementation identifier
2066
   * @returns {string} - The RMW implementation identifier.
2067
   */
2068
  getRMWImplementationIdentifier() {
2069
    return rclnodejs.getRMWImplementationIdentifier();
1✔
2070
  }
2071

2072
  /**
2073
   * Return a topic name expanded and remapped.
2074
   * @param {string} topicName - Topic name to be expanded and remapped.
2075
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2076
   * @returns {string} - A fully qualified topic name.
2077
   */
2078
  resolveTopicName(topicName, onlyExpand = false) {
2✔
2079
    if (typeof topicName !== 'string') {
3!
UNCOV
2080
      throw new TypeValidationError('topicName', topicName, 'string', {
×
2081
        nodeName: this.name(),
2082
      });
2083
    }
2084
    return rclnodejs.resolveName(
3✔
2085
      this.handle,
2086
      topicName,
2087
      onlyExpand,
2088
      /*isService=*/ false
2089
    );
2090
  }
2091

2092
  /**
2093
   * Return a service name expanded and remapped.
2094
   * @param {string} service - Service name to be expanded and remapped.
2095
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2096
   * @returns {string} - A fully qualified service name.
2097
   */
2098
  resolveServiceName(service, onlyExpand = false) {
6✔
2099
    if (typeof service !== 'string') {
7!
UNCOV
2100
      throw new TypeValidationError('service', service, 'string', {
×
2101
        nodeName: this.name(),
2102
      });
2103
    }
2104
    return rclnodejs.resolveName(
7✔
2105
      this.handle,
2106
      service,
2107
      onlyExpand,
2108
      /*isService=*/ true
2109
    );
2110
  }
2111

2112
  // returns on 1st error or result {successful, reason}
2113
  _validateParameters(parameters = [], declareParameterMode = false) {
×
2114
    for (const parameter of parameters) {
2,204✔
2115
      // detect invalid parameter
2116
      try {
2,204✔
2117
        parameter.validate();
2,204✔
2118
      } catch {
UNCOV
2119
        return {
×
2120
          successful: false,
2121
          reason: `Invalid ${parameter.name}`,
2122
        };
2123
      }
2124

2125
      // detect undeclared parameter
2126
      if (!this.hasParameterDescriptor(parameter.name)) {
2,204!
UNCOV
2127
        return {
×
2128
          successful: false,
2129
          reason: `Parameter ${parameter.name} has not been declared`,
2130
        };
2131
      }
2132

2133
      // detect readonly parameter that can not be updated
2134
      const descriptor = this.getParameterDescriptor(parameter.name);
2,204✔
2135
      if (!declareParameterMode && descriptor.readOnly) {
2,204!
UNCOV
2136
        return {
×
2137
          successful: false,
2138
          reason: `Parameter ${parameter.name} is readonly`,
2139
        };
2140
      }
2141

2142
      // validate parameter against descriptor if not an undeclare action
2143
      if (parameter.type != ParameterType.PARAMETER_NOT_SET) {
2,204✔
2144
        try {
2,203✔
2145
          descriptor.validateParameter(parameter);
2,203✔
2146
        } catch {
UNCOV
2147
          return {
×
2148
            successful: false,
2149
            reason: `Parameter ${parameter.name} does not  readonly`,
2150
          };
2151
        }
2152
      }
2153
    }
2154

2155
    return {
2,204✔
2156
      successful: true,
2157
      reason: null,
2158
    };
2159
  }
2160

2161
  // Get a Map(nodeName->Parameter[]) of CLI parameter args that
2162
  // apply to 'this' node, .e.g., -p mynode:foo:=bar -p hello:=world
2163
  _getNativeParameterOverrides() {
2164
    const overrides = new Map();
798✔
2165

2166
    // Get native parameters from rcl context->global_arguments.
2167
    // rclnodejs returns an array of objects, 1 for each node e.g., -p my_node:foo:=bar,
2168
    // and a node named '/**' for global parameter rules,
2169
    // i.e., does not include a node identifier, e.g., -p color:=red
2170
    // {
2171
    //   name: string // node name
2172
    //   parameters[] = {
2173
    //     name: string
2174
    //     type: uint
2175
    //     value: object
2176
    // }
2177
    const cliParamOverrideData = rclnodejs.getParameterOverrides(
798✔
2178
      this.context.handle
2179
    );
2180

2181
    // convert native CLI parameterOverrides to Map<nodeName,Array<ParameterOverride>>
2182
    const cliParamOverrides = new Map();
798✔
2183
    if (cliParamOverrideData) {
798✔
2184
      for (let nodeParamData of cliParamOverrideData) {
8✔
2185
        const nodeName = nodeParamData.name;
12✔
2186
        const nodeParamOverrides = [];
12✔
2187
        for (let paramData of nodeParamData.parameters) {
12✔
2188
          const paramOverride = new Parameter(
17✔
2189
            paramData.name,
2190
            paramData.type,
2191
            paramData.value
2192
          );
2193
          nodeParamOverrides.push(paramOverride);
17✔
2194
        }
2195
        cliParamOverrides.set(nodeName, nodeParamOverrides);
12✔
2196
      }
2197
    }
2198

2199
    // collect global CLI global parameters, name == /**
2200
    let paramOverrides = cliParamOverrides.get('/**'); // array of ParameterOverrides
798✔
2201
    if (paramOverrides) {
798✔
2202
      for (const parameter of paramOverrides) {
5✔
2203
        overrides.set(parameter.name, parameter);
6✔
2204
      }
2205
    }
2206

2207
    // merge CLI node parameterOverrides with global parameterOverrides, replace existing
2208
    paramOverrides = cliParamOverrides.get(this.name()); // array of ParameterOverrides
798✔
2209
    if (paramOverrides) {
798✔
2210
      for (const parameter of paramOverrides) {
5✔
2211
        overrides.set(parameter.name, parameter);
7✔
2212
      }
2213
    }
2214

2215
    return overrides;
798✔
2216
  }
2217

2218
  /**
2219
   * Invokes the callback with a raw message of the given type. After the callback completes
2220
   * the message will be destroyed.
2221
   * @param {function} Type - Message type to create.
2222
   * @param {function} callback - Callback to invoke. First parameter will be the raw message,
2223
   * and the second is a function to retrieve the deserialized message.
2224
   * @returns {undefined}
2225
   */
2226
  _runWithMessageType(Type, callback) {
2227
    let message = new Type();
960✔
2228

2229
    callback(message.toRawROS(), () => {
960✔
2230
      let result = new Type();
705✔
2231
      result.deserialize(message.refObject);
705✔
2232

2233
      return result;
705✔
2234
    });
2235

2236
    Type.destroyRawROS(message);
960✔
2237
  }
2238

2239
  _addActionClient(actionClient) {
2240
    this._actionClients.push(actionClient);
41✔
2241
    this.syncHandles();
41✔
2242
  }
2243

2244
  _addActionServer(actionServer) {
2245
    this._actionServers.push(actionServer);
41✔
2246
    this.syncHandles();
41✔
2247
  }
2248

2249
  _getValidatedTopic(topicName, noDemangle) {
2250
    if (noDemangle) {
6!
UNCOV
2251
      return topicName;
×
2252
    }
2253
    const fqTopicName = rclnodejs.expandTopicName(
6✔
2254
      topicName,
2255
      this.name(),
2256
      this.namespace()
2257
    );
2258
    validateFullTopicName(fqTopicName);
6✔
2259
    return rclnodejs.remapTopicName(this.handle, fqTopicName);
6✔
2260
  }
2261

2262
  _getValidatedServiceName(serviceName, noDemangle) {
2263
    if (typeof serviceName !== 'string') {
4!
UNCOV
2264
      throw new TypeValidationError('serviceName', serviceName, 'string', {
×
2265
        nodeName: this.name(),
2266
      });
2267
    }
2268

2269
    if (noDemangle) {
4!
UNCOV
2270
      return serviceName;
×
2271
    }
2272

2273
    const resolvedServiceName = this.resolveServiceName(serviceName);
4✔
2274
    rclnodejs.validateTopicName(resolvedServiceName);
4✔
2275
    return resolvedServiceName;
4✔
2276
  }
2277
}
2278

2279
/**
2280
 * Create an Options instance initialized with default values.
2281
 * @returns {Options} - The new initialized instance.
2282
 * @static
2283
 * @example
2284
 * {
2285
 *   enableTypedArray: true,
2286
 *   isRaw: false,
2287
 *   qos: QoS.profileDefault,
2288
 *   contentFilter: undefined,
2289
 *   serializationMode: 'default',
2290
 * }
2291
 */
2292
Node.getDefaultOptions = function () {
26✔
2293
  return {
7,437✔
2294
    enableTypedArray: true,
2295
    isRaw: false,
2296
    qos: QoS.profileDefault,
2297
    contentFilter: undefined,
2298
    serializationMode: 'default',
2299
  };
2300
};
2301

2302
module.exports = Node;
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