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

RobotWebTools / rclnodejs / 23230092275

18 Mar 2026 05:08AM UTC coverage: 85.995% (+0.03%) from 85.961%
23230092275

push

github

minggangw
Add waitForMessage utility for one-shot message reception (#1444)

Adds `waitForMessage()`, the rclnodejs equivalent of rclpy's `wait_for_message(msg_type, node, topic, time_to_wait)`. This utility creates a temporary subscription, waits for the first message to arrive on a topic, and returns it as a Promise. The temporary subscription is always cleaned up — on success, timeout, or error. Supports an optional timeout and QoS profile. The node must be spinning before calling this function.

**New files:**

- `lib/wait_for_message.js` — Core implementation. Creates a temporary subscription with a one-shot callback that resolves the Promise on first message. Uses a `settled` guard to prevent double-resolution. Cleanup runs unconditionally via the `settle()` helper. Accepts optional `{ timeout, qos }` options.
- `test/test-wait-for-message.js` — 7 tests covering: successful message reception, timeout rejection, first-message-only semantics, different message types (String, Int32), indefinite wait without timeout, subscription cleanup after receiving, and subscription cleanup on timeout.

**Modified files:**

- `index.js` — Added `require('./lib/wait_for_message.js')` and re-exported as `waitForMessage` property on the module.
- `types/index.d.ts` — Added `WaitForMessageOptions` interface and generic `waitForMessage<T>(typeClass, node, topic, options?)` function declaration.

Fix: #1443

1477 of 1866 branches covered (79.15%)

Branch coverage included in aggregate %.

29 of 32 new or added lines in 1 file covered. (90.63%)

59 existing lines in 3 files now uncovered.

3036 of 3382 relevant lines covered (89.77%)

458.08 hits per line

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

87.54
/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 ParameterEventHandler = require('./parameter_event_handler.js');
26✔
44
const Publisher = require('./publisher.js');
26✔
45
const QoS = require('./qos.js');
26✔
46
const Rates = require('./rate.js');
26✔
47
const Service = require('./service.js');
26✔
48
const Subscription = require('./subscription.js');
26✔
49
const ObservableSubscription = require('./observable_subscription.js');
26✔
50
const MessageInfo = require('./message_info.js');
26✔
51
const TimeSource = require('./time_source.js');
26✔
52
const Timer = require('./timer.js');
26✔
53
const TypeDescriptionService = require('./type_description_service.js');
26✔
54
const Entity = require('./entity.js');
26✔
55
const { SubscriptionEventCallbacks } = require('../lib/event_handler.js');
26✔
56
const { PublisherEventCallbacks } = require('../lib/event_handler.js');
26✔
57
const { validateFullTopicName } = require('./validator.js');
26✔
58

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

63
/**
64
 * @class - Class representing a Node in ROS
65
 */
66

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

87
    if (typeof nodeName !== 'string') {
901✔
88
      throw new TypeValidationError('nodeName', nodeName, 'string');
12✔
89
    }
90
    if (typeof namespace !== 'string') {
889✔
91
      throw new TypeValidationError('namespace', namespace, 'string');
10✔
92
    }
93

94
    this._init(nodeName, namespace, options, context, args, useGlobalArguments);
879✔
95
    debug(
868✔
96
      'Finish initializing node, name = %s and namespace = %s.',
97
      nodeName,
98
      namespace
99
    );
100
  }
101

102
  static _normalizeOptions(options) {
103
    if (options instanceof NodeOptions) {
879✔
104
      return options;
877✔
105
    }
106
    const defaults = NodeOptions.defaultOptions;
2✔
107
    return {
2✔
108
      startParameterServices:
109
        options.startParameterServices ?? defaults.startParameterServices,
4✔
110
      parameterOverrides:
111
        options.parameterOverrides ?? defaults.parameterOverrides,
4✔
112
      automaticallyDeclareParametersFromOverrides:
113
        options.automaticallyDeclareParametersFromOverrides ??
4✔
114
        defaults.automaticallyDeclareParametersFromOverrides,
115
      startTypeDescriptionService:
116
        options.startTypeDescriptionService ??
4✔
117
        defaults.startTypeDescriptionService,
118
      enableRosout: options.enableRosout ?? defaults.enableRosout,
3✔
119
      rosoutQos: options.rosoutQos ?? defaults.rosoutQos,
4✔
120
    };
121
  }
122

123
  _init(name, namespace, options, context, args, useGlobalArguments) {
124
    options = Node._normalizeOptions(options);
879✔
125

126
    this.handle = rclnodejs.createNode(
879✔
127
      name,
128
      namespace,
129
      context.handle,
130
      args,
131
      useGlobalArguments,
132
      options.rosoutQos
133
    );
134
    Object.defineProperty(this, 'handle', {
869✔
135
      configurable: false,
136
      writable: false,
137
    }); // make read-only
138

139
    this._context = context;
869✔
140
    this.context.onNodeCreated(this);
869✔
141

142
    this._publishers = [];
869✔
143
    this._subscriptions = [];
869✔
144
    this._clients = [];
869✔
145
    this._services = [];
869✔
146
    this._timers = [];
869✔
147
    this._guards = [];
869✔
148
    this._events = [];
869✔
149
    this._actionClients = [];
869✔
150
    this._actionServers = [];
869✔
151
    this._parameterClients = [];
869✔
152
    this._parameterWatchers = [];
869✔
153
    this._parameterEventHandlers = [];
869✔
154
    this._rateTimerServer = null;
869✔
155
    this._parameterDescriptors = new Map();
869✔
156
    this._parameters = new Map();
869✔
157
    this._parameterService = null;
869✔
158
    this._typeDescriptionService = null;
869✔
159
    this._parameterEventPublisher = null;
869✔
160
    this._setParametersCallbacks = [];
869✔
161
    this._logger = new Logging(rclnodejs.getNodeLoggerName(this.handle));
869✔
162
    this._spinning = false;
869✔
163
    this._enableRosout = options.enableRosout;
869✔
164

165
    if (this._enableRosout) {
869✔
166
      rclnodejs.initRosoutPublisherForNode(this.handle);
867✔
167
    }
168

169
    this._parameterEventPublisher = this.createPublisher(
869✔
170
      PARAMETER_EVENT_MSG_TYPE,
171
      PARAMETER_EVENT_TOPIC
172
    );
173

174
    // initialize _parameterOverrides from parameters defined on the commandline
175
    this._parameterOverrides = this._getNativeParameterOverrides();
869✔
176

177
    // override cli parameterOverrides with those specified in options
178
    if (options.parameterOverrides.length > 0) {
869✔
179
      for (const parameter of options.parameterOverrides) {
11✔
180
        if (!(parameter instanceof Parameter)) {
16✔
181
          throw new TypeValidationError(
1✔
182
            'parameterOverride',
183
            parameter,
184
            'Parameter instance',
185
            {
186
              nodeName: name,
187
            }
188
          );
189
        }
190
        this._parameterOverrides.set(parameter.name, parameter);
15✔
191
      }
192
    }
193

194
    // initialize _parameters from parameterOverrides
195
    if (options.automaticallyDeclareParametersFromOverrides) {
868✔
196
      for (const parameter of this._parameterOverrides.values()) {
5✔
197
        parameter.validate();
10✔
198
        const descriptor = ParameterDescriptor.fromParameter(parameter);
10✔
199
        this._parameters.set(parameter.name, parameter);
10✔
200
        this._parameterDescriptors.set(parameter.name, descriptor);
10✔
201
      }
202
    }
203

204
    // Clock that has support for ROS time.
205
    // Note: parameter overrides and parameter event publisher need to be ready at this point
206
    // to be able to declare 'use_sim_time' if it was not declared yet.
207
    this._clock = new Clock.ROSClock();
868✔
208
    this._timeSource = new TimeSource(this);
868✔
209
    this._timeSource.attachClock(this._clock);
868✔
210

211
    if (options.startParameterServices) {
868✔
212
      this._parameterService = new ParameterService(this);
862✔
213
      this._parameterService.start();
862✔
214
    }
215

216
    if (
868!
217
      DistroUtils.getDistroId() >= DistroUtils.getDistroId('jazzy') &&
1,736✔
218
      options.startTypeDescriptionService
219
    ) {
220
      this._typeDescriptionService = new TypeDescriptionService(this);
868✔
221
      this._typeDescriptionService.start();
868✔
222
    }
223
  }
224

225
  execute(handles) {
226
    let timersReady = this._timers.filter((timer) =>
5,930✔
227
      handles.includes(timer.handle)
4,927✔
228
    );
229
    let guardsReady = this._guards.filter((guard) =>
5,930✔
230
      handles.includes(guard.handle)
3✔
231
    );
232
    let subscriptionsReady = this._subscriptions.filter((subscription) =>
5,930✔
233
      handles.includes(subscription.handle)
533✔
234
    );
235
    let clientsReady = this._clients.filter((client) =>
5,930✔
236
      handles.includes(client.handle)
323✔
237
    );
238
    let servicesReady = this._services.filter((service) =>
5,930✔
239
      handles.includes(service.handle)
23,520✔
240
    );
241
    let actionClientsReady = this._actionClients.filter((actionClient) =>
5,930✔
242
      handles.includes(actionClient.handle)
161✔
243
    );
244
    let actionServersReady = this._actionServers.filter((actionServer) =>
5,930✔
245
      handles.includes(actionServer.handle)
156✔
246
    );
247
    let eventsReady = this._events.filter((event) =>
5,930✔
248
      handles.includes(event.handle)
4✔
249
    );
250

251
    timersReady.forEach((timer) => {
5,930✔
252
      if (timer.isReady()) {
4,913✔
253
        rclnodejs.callTimer(timer.handle);
4,839✔
254
        timer.callback();
4,839✔
255
      }
256
    });
257

258
    eventsReady.forEach((event) => {
5,930✔
259
      event.takeData();
4✔
260
    });
261

262
    for (const subscription of subscriptionsReady) {
5,930✔
263
      if (subscription.isDestroyed()) continue;
489✔
264
      if (subscription.isRaw) {
480✔
265
        let rawMessage = rclnodejs.rclTakeRaw(subscription.handle);
1✔
266
        if (rawMessage) {
1!
267
          subscription.processResponse(rawMessage);
1✔
268
        }
269
        continue;
1✔
270
      }
271

272
      this._runWithMessageType(
479✔
273
        subscription.typeClass,
274
        (message, deserialize) => {
275
          if (subscription.wantsMessageInfo) {
479✔
276
            let rawInfo = rclnodejs.rclTakeWithInfo(
4✔
277
              subscription.handle,
278
              message
279
            );
280
            if (rawInfo) {
4!
281
              subscription.processResponse(
4✔
282
                deserialize(),
283
                new MessageInfo(rawInfo)
284
              );
285
            }
286
          } else {
287
            let success = rclnodejs.rclTake(subscription.handle, message);
475✔
288
            if (success) {
475✔
289
              subscription.processResponse(deserialize());
388✔
290
            }
291
          }
292
        }
293
      );
294
    }
295

296
    for (const guard of guardsReady) {
5,930✔
297
      if (guard.isDestroyed()) continue;
3!
298

299
      guard.callback();
3✔
300
    }
301

302
    for (const client of clientsReady) {
5,930✔
303
      if (client.isDestroyed()) continue;
167!
304
      this._runWithMessageType(
167✔
305
        client.typeClass.Response,
306
        (message, deserialize) => {
307
          let sequenceNumber = rclnodejs.rclTakeResponse(
167✔
308
            client.handle,
309
            message
310
          );
311
          if (sequenceNumber !== undefined) {
167✔
312
            client.processResponse(sequenceNumber, deserialize());
86✔
313
          }
314
        }
315
      );
316
    }
317

318
    for (const service of servicesReady) {
5,930✔
319
      if (service.isDestroyed()) continue;
213!
320
      this._runWithMessageType(
213✔
321
        service.typeClass.Request,
322
        (message, deserialize) => {
323
          let header = rclnodejs.rclTakeRequest(
213✔
324
            service.handle,
325
            this.handle,
326
            message
327
          );
328
          if (header) {
213✔
329
            service.processRequest(header, deserialize());
92✔
330
          }
331
        }
332
      );
333
    }
334

335
    for (const actionClient of actionClientsReady) {
5,930✔
336
      if (actionClient.isDestroyed()) continue;
78!
337

338
      const properties = actionClient.handle.properties;
78✔
339

340
      if (properties.isGoalResponseReady) {
78✔
341
        this._runWithMessageType(
40✔
342
          actionClient.typeClass.impl.SendGoalService.Response,
343
          (message, deserialize) => {
344
            let sequence = rclnodejs.actionTakeGoalResponse(
40✔
345
              actionClient.handle,
346
              message
347
            );
348
            if (sequence != undefined) {
40✔
349
              actionClient.processGoalResponse(sequence, deserialize());
30✔
350
            }
351
          }
352
        );
353
      }
354

355
      if (properties.isCancelResponseReady) {
78✔
356
        this._runWithMessageType(
5✔
357
          actionClient.typeClass.impl.CancelGoal.Response,
358
          (message, deserialize) => {
359
            let sequence = rclnodejs.actionTakeCancelResponse(
5✔
360
              actionClient.handle,
361
              message
362
            );
363
            if (sequence != undefined) {
5✔
364
              actionClient.processCancelResponse(sequence, deserialize());
4✔
365
            }
366
          }
367
        );
368
      }
369

370
      if (properties.isResultResponseReady) {
78✔
371
        this._runWithMessageType(
15✔
372
          actionClient.typeClass.impl.GetResultService.Response,
373
          (message, deserialize) => {
374
            let sequence = rclnodejs.actionTakeResultResponse(
15✔
375
              actionClient.handle,
376
              message
377
            );
378
            if (sequence != undefined) {
15!
379
              actionClient.processResultResponse(sequence, deserialize());
15✔
380
            }
381
          }
382
        );
383
      }
384

385
      if (properties.isFeedbackReady) {
78✔
386
        this._runWithMessageType(
9✔
387
          actionClient.typeClass.impl.FeedbackMessage,
388
          (message, deserialize) => {
389
            let success = rclnodejs.actionTakeFeedback(
9✔
390
              actionClient.handle,
391
              message
392
            );
393
            if (success) {
9✔
394
              actionClient.processFeedbackMessage(deserialize());
5✔
395
            }
396
          }
397
        );
398
      }
399

400
      if (properties.isStatusReady) {
78✔
401
        this._runWithMessageType(
40✔
402
          actionClient.typeClass.impl.GoalStatusArray,
403
          (message, deserialize) => {
404
            let success = rclnodejs.actionTakeStatus(
40✔
405
              actionClient.handle,
406
              message
407
            );
408
            if (success) {
40✔
409
              actionClient.processStatusMessage(deserialize());
32✔
410
            }
411
          }
412
        );
413
      }
414
    }
415

416
    for (const actionServer of actionServersReady) {
5,930✔
417
      if (actionServer.isDestroyed()) continue;
92!
418

419
      const properties = actionServer.handle.properties;
92✔
420

421
      if (properties.isGoalRequestReady) {
92✔
422
        this._runWithMessageType(
32✔
423
          actionServer.typeClass.impl.SendGoalService.Request,
424
          (message, deserialize) => {
425
            const result = rclnodejs.actionTakeGoalRequest(
32✔
426
              actionServer.handle,
427
              message
428
            );
429
            if (result) {
32✔
430
              actionServer.processGoalRequest(result, deserialize());
30✔
431
            }
432
          }
433
        );
434
      }
435

436
      if (properties.isCancelRequestReady) {
92✔
437
        this._runWithMessageType(
7✔
438
          actionServer.typeClass.impl.CancelGoal.Request,
439
          (message, deserialize) => {
440
            const result = rclnodejs.actionTakeCancelRequest(
7✔
441
              actionServer.handle,
442
              message
443
            );
444
            if (result) {
7✔
445
              actionServer.processCancelRequest(result, deserialize());
4✔
446
            }
447
          }
448
        );
449
      }
450

451
      if (properties.isResultRequestReady) {
92✔
452
        this._runWithMessageType(
22✔
453
          actionServer.typeClass.impl.GetResultService.Request,
454
          (message, deserialize) => {
455
            const result = rclnodejs.actionTakeResultRequest(
22✔
456
              actionServer.handle,
457
              message
458
            );
459
            if (result) {
22✔
460
              actionServer.processResultRequest(result, deserialize());
15✔
461
            }
462
          }
463
        );
464
      }
465

466
      if (properties.isGoalExpired) {
92✔
467
        let numGoals = actionServer._goalHandles.size;
4✔
468
        if (numGoals > 0) {
4✔
469
          let GoalInfoArray = ActionInterfaces.GoalInfo.ArrayType;
3✔
470
          let message = new GoalInfoArray(numGoals);
3✔
471
          let count = rclnodejs.actionExpireGoals(
3✔
472
            actionServer.handle,
473
            numGoals,
474
            message._refArray.buffer
475
          );
476
          if (count > 0) {
3!
477
            actionServer.processGoalExpired(message, count);
3✔
478
          }
479
          GoalInfoArray.freeArray(message);
3✔
480
        }
481
      }
482
    }
483

484
    // At this point it is safe to clear the cache of any
485
    // destroyed entity references
486
    Entity._gcHandles();
5,930✔
487
  }
488

489
  /**
490
   * Determine if this node is spinning.
491
   * @returns {boolean} - true when spinning; otherwise returns false.
492
   */
493
  get spinning() {
494
    return this._spinning;
4,584✔
495
  }
496

497
  /**
498
   * Trigger the event loop to continuously check for and route.
499
   * incoming events.
500
   * @param {Node} node - The node to be spun up.
501
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
502
   * @throws {Error} If the node is already spinning.
503
   * @return {undefined}
504
   */
505
  spin(timeout = 10) {
26✔
506
    if (this.spinning) {
681!
UNCOV
507
      throw new Error('The node is already spinning.');
×
508
    }
509
    this.start(this.context.handle, timeout);
681✔
510
    this._spinning = true;
681✔
511
  }
512

513
  /**
514
   * Use spin().
515
   * @deprecated, since 0.18.0
516
   */
517
  startSpinning(timeout) {
UNCOV
518
    this.spin(timeout);
×
519
  }
520

521
  /**
522
   * Terminate spinning - no further events will be received.
523
   * @returns {undefined}
524
   */
525
  stop() {
526
    super.stop();
681✔
527
    this._spinning = false;
681✔
528
  }
529

530
  /**
531
   * Terminate spinning - no further events will be received.
532
   * @returns {undefined}
533
   * @deprecated since 0.18.0, Use stop().
534
   */
535
  stopSpinning() {
UNCOV
536
    super.stop();
×
UNCOV
537
    this._spinning = false;
×
538
  }
539

540
  /**
541
   * Spin the node and trigger the event loop to check for one incoming event. Thereafter the node
542
   * will not received additional events until running additional calls to spin() or spinOnce().
543
   * @param {Node} node - The node to be spun.
544
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
545
   * @throws {Error} If the node is already spinning.
546
   * @return {undefined}
547
   */
548
  spinOnce(timeout = 10) {
2✔
549
    if (this.spinning) {
3,009✔
550
      throw new Error('The node is already spinning.');
2✔
551
    }
552
    super.spinOnce(this.context.handle, timeout);
3,007✔
553
  }
554

555
  _removeEntityFromArray(entity, array) {
556
    let index = array.indexOf(entity);
369✔
557
    if (index > -1) {
369✔
558
      array.splice(index, 1);
367✔
559
    }
560
  }
561

562
  _destroyEntity(entity, array, syncHandles = true) {
314✔
563
    if (entity['isDestroyed'] && entity.isDestroyed()) return;
321✔
564

565
    this._removeEntityFromArray(entity, array);
313✔
566
    if (syncHandles) {
313✔
567
      this.syncHandles();
308✔
568
    }
569

570
    if (entity['_destroy']) {
313✔
571
      entity._destroy();
307✔
572
    } else {
573
      // guards and timers
574
      entity.handle.release();
6✔
575
    }
576
  }
577

578
  _validateOptions(options) {
579
    if (
8,066✔
580
      options !== undefined &&
8,154✔
581
      (options === null || typeof options !== 'object')
582
    ) {
583
      throw new TypeValidationError('options', options, 'object', {
20✔
584
        nodeName: this.name(),
585
      });
586
    }
587

588
    if (options === undefined) {
8,046✔
589
      return Node.getDefaultOptions();
8,012✔
590
    }
591

592
    if (options.enableTypedArray === undefined) {
34✔
593
      options = Object.assign(options, { enableTypedArray: true });
20✔
594
    }
595

596
    if (options.qos === undefined) {
34✔
597
      options = Object.assign(options, { qos: QoS.profileDefault });
20✔
598
    }
599

600
    if (options.isRaw === undefined) {
34✔
601
      options = Object.assign(options, { isRaw: false });
23✔
602
    }
603

604
    if (options.serializationMode === undefined) {
34✔
605
      options = Object.assign(options, { serializationMode: 'default' });
17✔
606
    } else if (!isValidSerializationMode(options.serializationMode)) {
17✔
607
      throw new ValidationError(
1✔
608
        `Invalid serializationMode: ${options.serializationMode}. Valid modes are: 'default', 'plain', 'json'`,
609
        {
610
          code: 'INVALID_SERIALIZATION_MODE',
611
          argumentName: 'serializationMode',
612
          providedValue: options.serializationMode,
613
          expectedType: "'default' | 'plain' | 'json'",
614
          nodeName: this.name(),
615
        }
616
      );
617
    }
618

619
    return options;
33✔
620
  }
621

622
  /**
623
   * Create a Timer.
624
   * @param {bigint} period - The number representing period in nanoseconds.
625
   * @param {function} callback - The callback to be called when timeout.
626
   * @param {Clock} [clock] - The clock which the timer gets time from.
627
   * @return {Timer} - An instance of Timer.
628
   */
629
  createTimer(period, callback, clock = null) {
67✔
630
    if (arguments.length === 3 && !(arguments[2] instanceof Clock)) {
67!
UNCOV
631
      clock = null;
×
632
    } else if (arguments.length === 4) {
67!
UNCOV
633
      clock = arguments[3];
×
634
    }
635

636
    if (typeof period !== 'bigint') {
67✔
637
      throw new TypeValidationError('period', period, 'bigint', {
1✔
638
        nodeName: this.name(),
639
      });
640
    }
641
    if (typeof callback !== 'function') {
66✔
642
      throw new TypeValidationError('callback', callback, 'function', {
1✔
643
        nodeName: this.name(),
644
      });
645
    }
646

647
    const timerClock = clock || this._clock;
65✔
648
    let timerHandle = rclnodejs.createTimer(
65✔
649
      timerClock.handle,
650
      this.context.handle,
651
      period
652
    );
653
    let timer = new Timer(timerHandle, period, callback);
65✔
654
    debug('Finish creating timer, period = %d.', period);
65✔
655
    this._timers.push(timer);
65✔
656
    this.syncHandles();
65✔
657

658
    return timer;
65✔
659
  }
660

661
  /**
662
   * Create a Rate.
663
   *
664
   * @param {number} hz - The frequency of the rate timer; default is 1 hz.
665
   * @returns {Promise<Rate>} - Promise resolving to new instance of Rate.
666
   */
667
  async createRate(hz = 1) {
4✔
668
    if (typeof hz !== 'number') {
9!
UNCOV
669
      throw new TypeValidationError('hz', hz, 'number', {
×
670
        nodeName: this.name(),
671
      });
672
    }
673

674
    const MAX_RATE_HZ_IN_MILLISECOND = 1000.0;
9✔
675
    if (hz <= 0.0 || hz > MAX_RATE_HZ_IN_MILLISECOND) {
9✔
676
      throw new RangeValidationError(
2✔
677
        'hz',
678
        hz,
679
        `0.0 < hz <= ${MAX_RATE_HZ_IN_MILLISECOND}`,
680
        {
681
          nodeName: this.name(),
682
        }
683
      );
684
    }
685

686
    // lazy initialize rateTimerServer
687
    if (!this._rateTimerServer) {
7✔
688
      this._rateTimerServer = new Rates.RateTimerServer(this);
5✔
689
      await this._rateTimerServer.init();
5✔
690
    }
691

692
    const period = Math.round(1000 / hz);
7✔
693
    const timer = this._rateTimerServer.createTimer(BigInt(period) * 1000000n);
7✔
694
    const rate = new Rates.Rate(hz, timer);
7✔
695

696
    return rate;
7✔
697
  }
698

699
  /**
700
   * Create a Publisher.
701
   * @param {function|string|object} typeClass - The ROS message class,
702
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
703
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
704
   * @param {string} topic - The name of the topic.
705
   * @param {object} options - The options argument used to parameterize the publisher.
706
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
707
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the publisher, default: QoS.profileDefault.
708
   * @param {PublisherEventCallbacks} eventCallbacks - The event callbacks for the publisher.
709
   * @return {Publisher} - An instance of Publisher.
710
   */
711
  createPublisher(typeClass, topic, options, eventCallbacks) {
712
    return this._createPublisher(
1,242✔
713
      typeClass,
714
      topic,
715
      options,
716
      Publisher,
717
      eventCallbacks
718
    );
719
  }
720

721
  _createPublisher(typeClass, topic, options, publisherClass, eventCallbacks) {
722
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
1,245✔
723
      typeClass = loader.loadInterface(typeClass);
1,221✔
724
    }
725
    options = this._validateOptions(options);
1,238✔
726

727
    if (typeof typeClass !== 'function') {
1,238✔
728
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
729
        nodeName: this.name(),
730
        entityType: 'publisher',
731
      });
732
    }
733
    if (typeof topic !== 'string') {
1,230✔
734
      throw new TypeValidationError('topic', topic, 'string', {
12✔
735
        nodeName: this.name(),
736
        entityType: 'publisher',
737
      });
738
    }
739
    if (
1,218!
740
      eventCallbacks &&
1,220✔
741
      !(eventCallbacks instanceof PublisherEventCallbacks)
742
    ) {
UNCOV
743
      throw new TypeValidationError(
×
744
        'eventCallbacks',
745
        eventCallbacks,
746
        'PublisherEventCallbacks',
747
        {
748
          nodeName: this.name(),
749
          entityType: 'publisher',
750
          entityName: topic,
751
        }
752
      );
753
    }
754

755
    let publisher = publisherClass.createPublisher(
1,218✔
756
      this,
757
      typeClass,
758
      topic,
759
      options,
760
      eventCallbacks
761
    );
762
    debug('Finish creating publisher, topic = %s.', topic);
1,208✔
763
    this._publishers.push(publisher);
1,208✔
764
    return publisher;
1,208✔
765
  }
766

767
  /**
768
   * This callback is called when a message is published
769
   * @callback SubscriptionCallback
770
   * @param {Object} message - The message published
771
   * @see [Node.createSubscription]{@link Node#createSubscription}
772
   * @see [Node.createPublisher]{@link Node#createPublisher}
773
   * @see {@link Publisher}
774
   * @see {@link Subscription}
775
   */
776

777
  /**
778
   * Create a Subscription with optional content-filtering.
779
   * @param {function|string|object} typeClass - The ROS message class,
780
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
781
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
782
   * @param {string} topic - The name of the topic.
783
   * @param {object} options - The options argument used to parameterize the subscription.
784
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
785
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the subscription, default: QoS.profileDefault.
786
   * @param {boolean} options.isRaw - The topic is serialized when true, default: false.
787
   * @param {string} [options.serializationMode='default'] - Controls message serialization format:
788
   *  'default': Use native rclnodejs behavior (respects enableTypedArray setting),
789
   *  'plain': Convert TypedArrays to regular arrays,
790
   *  'json': Fully JSON-safe (handles TypedArrays, BigInt, etc.).
791
   * @param {object} [options.contentFilter=undefined] - The content-filter, default: undefined.
792
   *  Confirm that your RMW supports content-filtered topics before use. 
793
   * @param {string} options.contentFilter.expression - Specifies the criteria to select the data samples of
794
   *  interest. It is similar to the WHERE part of an SQL clause.
795
   * @param {string[]} [options.contentFilter.parameters=undefined] - Array of strings that give values to
796
   *  the ‘parameters’ (i.e., "%n" tokens) in the filter_expression. The number of supplied parameters must
797
   *  fit with the requested values in the filter_expression (i.e., the number of %n tokens). default: undefined.
798
   * @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.
799
   * @param {SubscriptionEventCallbacks} eventCallbacks - The event callbacks for the subscription.
800
   * @return {Subscription} - An instance of Subscription.
801
   * @throws {ERROR} - May throw an RMW error if content-filter is malformed. 
802
   * @see {@link SubscriptionCallback}
803
   * @see {@link https://www.omg.org/spec/DDS/1.4/PDF|Content-filter details at DDS 1.4 specification, Annex B}
804
   */
805
  createSubscription(typeClass, topic, options, callback, eventCallbacks) {
806
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
464✔
807
      typeClass = loader.loadInterface(typeClass);
455✔
808
    }
809

810
    if (typeof options === 'function') {
457✔
811
      callback = options;
342✔
812
      options = undefined;
342✔
813
    }
814
    options = this._validateOptions(options);
457✔
815

816
    if (typeof typeClass !== 'function') {
447✔
817
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
818
        nodeName: this.name(),
819
        entityType: 'subscription',
820
      });
821
    }
822
    if (typeof topic !== 'string') {
443✔
823
      throw new TypeValidationError('topic', topic, 'string', {
6✔
824
        nodeName: this.name(),
825
        entityType: 'subscription',
826
      });
827
    }
828
    if (typeof callback !== 'function') {
437!
UNCOV
829
      throw new TypeValidationError('callback', callback, 'function', {
×
830
        nodeName: this.name(),
831
        entityType: 'subscription',
832
        entityName: topic,
833
      });
834
    }
835
    if (
437!
836
      eventCallbacks &&
441✔
837
      !(eventCallbacks instanceof SubscriptionEventCallbacks)
838
    ) {
UNCOV
839
      throw new TypeValidationError(
×
840
        'eventCallbacks',
841
        eventCallbacks,
842
        'SubscriptionEventCallbacks',
843
        {
844
          nodeName: this.name(),
845
          entityType: 'subscription',
846
          entityName: topic,
847
        }
848
      );
849
    }
850

851
    let subscription = Subscription.createSubscription(
437✔
852
      this,
853
      typeClass,
854
      topic,
855
      options,
856
      callback,
857
      eventCallbacks
858
    );
859
    debug('Finish creating subscription, topic = %s.', topic);
426✔
860
    this._subscriptions.push(subscription);
426✔
861
    this.syncHandles();
426✔
862

863
    return subscription;
426✔
864
  }
865

866
  /**
867
   * Create a Subscription that returns an RxJS Observable.
868
   * This allows using reactive programming patterns with ROS 2 messages.
869
   *
870
   * @param {function|string|object} typeClass - The ROS message class,
871
   *      OR a string representing the message class, e.g. 'std_msgs/msg/String',
872
   *      OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
873
   * @param {string} topic - The name of the topic.
874
   * @param {object} [options] - The options argument used to parameterize the subscription.
875
   * @param {boolean} [options.enableTypedArray=true] - The topic will use TypedArray if necessary.
876
   * @param {QoS} [options.qos=QoS.profileDefault] - ROS Middleware "quality of service" settings.
877
   * @param {boolean} [options.isRaw=false] - The topic is serialized when true.
878
   * @param {string} [options.serializationMode='default'] - Controls message serialization format.
879
   * @param {object} [options.contentFilter] - The content-filter (if supported by RMW).
880
   * @param {SubscriptionEventCallbacks} [eventCallbacks] - The event callbacks for the subscription.
881
   * @return {ObservableSubscription} - An ObservableSubscription with an RxJS Observable.
882
   */
883
  createObservableSubscription(typeClass, topic, options, eventCallbacks) {
884
    let observableSubscription = null;
7✔
885

886
    const subscription = this.createSubscription(
7✔
887
      typeClass,
888
      topic,
889
      options,
890
      (message) => {
891
        if (observableSubscription) {
8!
892
          observableSubscription._emit(message);
8✔
893
        }
894
      },
895
      eventCallbacks
896
    );
897

898
    observableSubscription = new ObservableSubscription(subscription);
7✔
899
    return observableSubscription;
7✔
900
  }
901

902
  /**
903
   * Create a Client.
904
   * @param {function|string|object} typeClass - The ROS message class,
905
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
906
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
907
   * @param {string} serviceName - The service name to request.
908
   * @param {object} options - The options argument used to parameterize the client.
909
   * @param {boolean} options.enableTypedArray - The response will use TypedArray if necessary, default: true.
910
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the client, default: QoS.profileDefault.
911
   * @return {Client} - An instance of Client.
912
   */
913
  createClient(typeClass, serviceName, options) {
914
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
196✔
915
      typeClass = loader.loadInterface(typeClass);
186✔
916
    }
917
    options = this._validateOptions(options);
189✔
918

919
    if (typeof typeClass !== 'function') {
189✔
920
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
921
        nodeName: this.name(),
922
        entityType: 'client',
923
      });
924
    }
925
    if (typeof serviceName !== 'string') {
181✔
926
      throw new TypeValidationError('serviceName', serviceName, 'string', {
12✔
927
        nodeName: this.name(),
928
        entityType: 'client',
929
      });
930
    }
931

932
    let client = Client.createClient(
169✔
933
      this.handle,
934
      serviceName,
935
      typeClass,
936
      options
937
    );
938
    debug('Finish creating client, service = %s.', serviceName);
159✔
939
    this._clients.push(client);
159✔
940
    this.syncHandles();
159✔
941

942
    return client;
159✔
943
  }
944

945
  /**
946
   * This callback is called when a request is sent to service
947
   * @callback RequestCallback
948
   * @param {Object} request - The request sent to the service
949
   * @param {Response} response - The response to client.
950
        Use [response.send()]{@link Response#send} to send response object to client
951
   * @return {undefined}
952
   * @see [Node.createService]{@link Node#createService}
953
   * @see [Client.sendRequest]{@link Client#sendRequest}
954
   * @see {@link Client}
955
   * @see {@link Service}
956
   * @see {@link Response#send}
957
   */
958

959
  /**
960
   * Create a Service.
961
   * @param {function|string|object} typeClass - The ROS message class,
962
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
963
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
964
   * @param {string} serviceName - The service name to offer.
965
   * @param {object} options - The options argument used to parameterize the service.
966
   * @param {boolean} options.enableTypedArray - The request will use TypedArray if necessary, default: true.
967
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the service, default: QoS.profileDefault.
968
   * @param {RequestCallback} callback - The callback to be called when receiving request.
969
   * @return {Service} - An instance of Service.
970
   * @see {@link RequestCallback}
971
   */
972
  createService(typeClass, serviceName, options, callback) {
973
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
5,245✔
974
      typeClass = loader.loadInterface(typeClass);
5,235✔
975
    }
976

977
    if (typeof options === 'function') {
5,238✔
978
      callback = options;
5,215✔
979
      options = undefined;
5,215✔
980
    }
981
    options = this._validateOptions(options);
5,238✔
982

983
    if (typeof typeClass !== 'function') {
5,228✔
984
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
985
        nodeName: this.name(),
986
        entityType: 'service',
987
      });
988
    }
989
    if (typeof serviceName !== 'string') {
5,224✔
990
      throw new TypeValidationError('serviceName', serviceName, 'string', {
6✔
991
        nodeName: this.name(),
992
        entityType: 'service',
993
      });
994
    }
995
    if (typeof callback !== 'function') {
5,218!
UNCOV
996
      throw new TypeValidationError('callback', callback, 'function', {
×
997
        nodeName: this.name(),
998
        entityType: 'service',
999
        entityName: serviceName,
1000
      });
1001
    }
1002

1003
    let service = Service.createService(
5,218✔
1004
      this.handle,
1005
      serviceName,
1006
      typeClass,
1007
      options,
1008
      callback
1009
    );
1010
    debug('Finish creating service, service = %s.', serviceName);
5,208✔
1011
    this._services.push(service);
5,208✔
1012
    this.syncHandles();
5,208✔
1013

1014
    return service;
5,208✔
1015
  }
1016

1017
  /**
1018
   * Create a ParameterClient for accessing parameters on a remote node.
1019
   * @param {string} remoteNodeName - The name of the remote node whose parameters to access.
1020
   * @param {object} [options] - Options for parameter client.
1021
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
1022
   * @return {ParameterClient} - An instance of ParameterClient.
1023
   */
1024
  createParameterClient(remoteNodeName, options = {}) {
50✔
1025
    if (typeof remoteNodeName !== 'string' || remoteNodeName.trim() === '') {
103!
UNCOV
1026
      throw new TypeError('Remote node name must be a non-empty string');
×
1027
    }
1028

1029
    const parameterClient = new ParameterClient(this, remoteNodeName, options);
103✔
1030
    debug(
103✔
1031
      'Finish creating parameter client for remote node = %s.',
1032
      remoteNodeName
1033
    );
1034
    this._parameterClients.push(parameterClient);
103✔
1035

1036
    return parameterClient;
103✔
1037
  }
1038

1039
  /**
1040
   * Create a ParameterWatcher for watching parameter changes on a remote node.
1041
   * @param {string} remoteNodeName - The name of the remote node whose parameters to watch.
1042
   * @param {string[]} parameterNames - Array of parameter names to watch.
1043
   * @param {object} [options] - Options for parameter watcher.
1044
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
1045
   * @return {ParameterWatcher} - An instance of ParameterWatcher.
1046
   */
1047
  createParameterWatcher(remoteNodeName, parameterNames, options = {}) {
56✔
1048
    const watcher = new ParameterWatcher(
57✔
1049
      this,
1050
      remoteNodeName,
1051
      parameterNames,
1052
      options
1053
    );
1054
    debug(
53✔
1055
      'Finish creating parameter watcher for remote node = %s.',
1056
      remoteNodeName
1057
    );
1058
    this._parameterWatchers.push(watcher);
53✔
1059

1060
    return watcher;
53✔
1061
  }
1062

1063
  /**
1064
   * Create a guard condition.
1065
   * @param {Function} callback - The callback to be called when the guard condition is triggered.
1066
   * @return {GuardCondition} - An instance of GuardCondition.
1067
   */
1068
  createGuardCondition(callback) {
1069
    if (typeof callback !== 'function') {
3!
UNCOV
1070
      throw new TypeValidationError('callback', callback, 'function', {
×
1071
        nodeName: this.name(),
1072
        entityType: 'guard_condition',
1073
      });
1074
    }
1075

1076
    let guard = GuardCondition.createGuardCondition(callback, this.context);
3✔
1077
    debug('Finish creating guard condition');
3✔
1078
    this._guards.push(guard);
3✔
1079
    this.syncHandles();
3✔
1080

1081
    return guard;
3✔
1082
  }
1083

1084
  /**
1085
   * Destroy all resource allocated by this node, including
1086
   * <code>Timer</code>s/<code>Publisher</code>s/<code>Subscription</code>s
1087
   * /<code>Client</code>s/<code>Service</code>s
1088
   * @return {undefined}
1089
   */
1090
  destroy() {
1091
    if (this.spinning) {
892✔
1092
      this.stop();
589✔
1093
    }
1094

1095
    // Action servers/clients require manual destruction due to circular reference with goal handles.
1096
    this._actionClients.forEach((actionClient) => actionClient.destroy());
892✔
1097
    this._actionServers.forEach((actionServer) => actionServer.destroy());
892✔
1098

1099
    this._parameterClients.forEach((paramClient) => paramClient.destroy());
892✔
1100
    this._parameterWatchers.forEach((watcher) => watcher.destroy());
892✔
1101
    this._parameterEventHandlers.forEach((handler) => handler.destroy());
892✔
1102

1103
    this.context.onNodeDestroyed(this);
892✔
1104

1105
    if (this._enableRosout) {
892✔
1106
      rclnodejs.finiRosoutPublisherForNode(this.handle);
867✔
1107
      this._enableRosout = false;
867✔
1108
    }
1109

1110
    this.handle.release();
892✔
1111
    this._clock = null;
892✔
1112
    this._timers = [];
892✔
1113
    this._publishers = [];
892✔
1114
    this._subscriptions = [];
892✔
1115
    this._clients = [];
892✔
1116
    this._services = [];
892✔
1117
    this._guards = [];
892✔
1118
    this._actionClients = [];
892✔
1119
    this._actionServers = [];
892✔
1120
    this._parameterClients = [];
892✔
1121
    this._parameterWatchers = [];
892✔
1122
    this._parameterEventHandlers = [];
892✔
1123

1124
    if (this._rateTimerServer) {
892✔
1125
      this._rateTimerServer.shutdown();
5✔
1126
      this._rateTimerServer = null;
5✔
1127
    }
1128
  }
1129

1130
  /**
1131
   * Destroy a Publisher.
1132
   * @param {Publisher} publisher - The Publisher to be destroyed.
1133
   * @return {undefined}
1134
   */
1135
  destroyPublisher(publisher) {
1136
    if (!(publisher instanceof Publisher)) {
9✔
1137
      throw new TypeValidationError(
2✔
1138
        'publisher',
1139
        publisher,
1140
        'Publisher instance',
1141
        {
1142
          nodeName: this.name(),
1143
        }
1144
      );
1145
    }
1146
    if (publisher.events) {
7!
UNCOV
1147
      publisher.events.forEach((event) => {
×
UNCOV
1148
        this._destroyEntity(event, this._events);
×
1149
      });
UNCOV
1150
      publisher.events = [];
×
1151
    }
1152
    this._destroyEntity(publisher, this._publishers, false);
7✔
1153
  }
1154

1155
  /**
1156
   * Destroy a Subscription.
1157
   * @param {Subscription} subscription - The Subscription to be destroyed.
1158
   * @return {undefined}
1159
   */
1160
  destroySubscription(subscription) {
1161
    if (!(subscription instanceof Subscription)) {
109✔
1162
      throw new TypeValidationError(
2✔
1163
        'subscription',
1164
        subscription,
1165
        'Subscription instance',
1166
        {
1167
          nodeName: this.name(),
1168
        }
1169
      );
1170
    }
1171
    if (subscription.events) {
107✔
1172
      subscription.events.forEach((event) => {
1✔
1173
        this._destroyEntity(event, this._events);
1✔
1174
      });
1175
      subscription.events = [];
1✔
1176
    }
1177

1178
    this._destroyEntity(subscription, this._subscriptions);
107✔
1179
  }
1180

1181
  /**
1182
   * Destroy a Client.
1183
   * @param {Client} client - The Client to be destroyed.
1184
   * @return {undefined}
1185
   */
1186
  destroyClient(client) {
1187
    if (!(client instanceof Client)) {
117✔
1188
      throw new TypeValidationError('client', client, 'Client instance', {
2✔
1189
        nodeName: this.name(),
1190
      });
1191
    }
1192
    this._destroyEntity(client, this._clients);
115✔
1193
  }
1194

1195
  /**
1196
   * Destroy a Service.
1197
   * @param {Service} service - The Service to be destroyed.
1198
   * @return {undefined}
1199
   */
1200
  destroyService(service) {
1201
    if (!(service instanceof Service)) {
8✔
1202
      throw new TypeValidationError('service', service, 'Service instance', {
2✔
1203
        nodeName: this.name(),
1204
      });
1205
    }
1206
    this._destroyEntity(service, this._services);
6✔
1207
  }
1208

1209
  /**
1210
   * Destroy a ParameterClient.
1211
   * @param {ParameterClient} parameterClient - The ParameterClient to be destroyed.
1212
   * @return {undefined}
1213
   */
1214
  destroyParameterClient(parameterClient) {
1215
    if (!(parameterClient instanceof ParameterClient)) {
54!
UNCOV
1216
      throw new TypeError('Invalid argument');
×
1217
    }
1218
    this._removeEntityFromArray(parameterClient, this._parameterClients);
54✔
1219
    parameterClient.destroy();
54✔
1220
  }
1221

1222
  /**
1223
   * Destroy a ParameterWatcher.
1224
   * @param {ParameterWatcher} watcher - The ParameterWatcher to be destroyed.
1225
   * @return {undefined}
1226
   */
1227
  destroyParameterWatcher(watcher) {
1228
    if (!(watcher instanceof ParameterWatcher)) {
1!
UNCOV
1229
      throw new TypeError('Invalid argument');
×
1230
    }
1231
    this._removeEntityFromArray(watcher, this._parameterWatchers);
1✔
1232
    watcher.destroy();
1✔
1233
  }
1234

1235
  /**
1236
   * Create a ParameterEventHandler that monitors parameter changes on any node.
1237
   *
1238
   * Unlike {@link ParameterWatcher} which watches specific parameters on a single
1239
   * remote node, ParameterEventHandler can register callbacks for parameters on
1240
   * any node in the ROS 2 graph by subscribing to /parameter_events.
1241
   *
1242
   * @param {object} [options] - Options for the handler
1243
   * @param {object} [options.qos] - QoS profile for the parameter_events subscription
1244
   * @return {ParameterEventHandler} - An instance of ParameterEventHandler
1245
   * @see {@link ParameterEventHandler}
1246
   */
1247
  createParameterEventHandler(options = {}) {
18✔
1248
    const handler = new ParameterEventHandler(this, options);
18✔
1249
    debug('Created ParameterEventHandler on node=%s', this.name());
18✔
1250
    this._parameterEventHandlers.push(handler);
18✔
1251
    return handler;
18✔
1252
  }
1253

1254
  /**
1255
   * Destroy a ParameterEventHandler.
1256
   * @param {ParameterEventHandler} handler - The handler to be destroyed.
1257
   * @return {undefined}
1258
   */
1259
  destroyParameterEventHandler(handler) {
1260
    if (!(handler instanceof ParameterEventHandler)) {
1!
UNCOV
1261
      throw new TypeError('Invalid argument');
×
1262
    }
1263
    this._removeEntityFromArray(handler, this._parameterEventHandlers);
1✔
1264
    handler.destroy();
1✔
1265
  }
1266

1267
  /**
1268
   * Destroy a Timer.
1269
   * @param {Timer} timer - The Timer to be destroyed.
1270
   * @return {undefined}
1271
   */
1272
  destroyTimer(timer) {
1273
    if (!(timer instanceof Timer)) {
8✔
1274
      throw new TypeValidationError('timer', timer, 'Timer instance', {
2✔
1275
        nodeName: this.name(),
1276
      });
1277
    }
1278
    this._destroyEntity(timer, this._timers);
6✔
1279
  }
1280

1281
  /**
1282
   * Destroy a guard condition.
1283
   * @param {GuardCondition} guard - The guard condition to be destroyed.
1284
   * @return {undefined}
1285
   */
1286
  destroyGuardCondition(guard) {
1287
    if (!(guard instanceof GuardCondition)) {
3!
UNCOV
1288
      throw new TypeValidationError('guard', guard, 'GuardCondition instance', {
×
1289
        nodeName: this.name(),
1290
      });
1291
    }
1292
    this._destroyEntity(guard, this._guards);
3✔
1293
  }
1294

1295
  /**
1296
   * Get the name of the node.
1297
   * @return {string}
1298
   */
1299
  name() {
1300
    return rclnodejs.getNodeName(this.handle);
5,201✔
1301
  }
1302

1303
  /**
1304
   * Get the namespace of the node.
1305
   * @return {string}
1306
   */
1307
  namespace() {
1308
    return rclnodejs.getNamespace(this.handle);
4,824✔
1309
  }
1310

1311
  /**
1312
   * Get the context in which this node was created.
1313
   * @return {Context}
1314
   */
1315
  get context() {
1316
    return this._context;
6,386✔
1317
  }
1318

1319
  /**
1320
   * Get the nodes logger.
1321
   * @returns {Logger} - The logger for the node.
1322
   */
1323
  getLogger() {
1324
    return this._logger;
146✔
1325
  }
1326

1327
  /**
1328
   * Get the clock used by the node.
1329
   * @returns {Clock} - The nodes clock.
1330
   */
1331
  getClock() {
1332
    return this._clock;
86✔
1333
  }
1334

1335
  /**
1336
   * Get the current time using the node's clock.
1337
   * @returns {Timer} - The current time.
1338
   */
1339
  now() {
1340
    return this.getClock().now();
2✔
1341
  }
1342

1343
  /**
1344
   * Get the list of published topics discovered by the provided node for the remote node name.
1345
   * @param {string} nodeName - The name of the node.
1346
   * @param {string} namespace - The name of the namespace.
1347
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1348
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1349
   */
1350
  getPublisherNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
2✔
1351
    return rclnodejs.getPublisherNamesAndTypesByNode(
2✔
1352
      this.handle,
1353
      nodeName,
1354
      namespace,
1355
      noDemangle
1356
    );
1357
  }
1358

1359
  /**
1360
   * Get the list of published topics discovered by the provided node for the remote node name.
1361
   * @param {string} nodeName - The name of the node.
1362
   * @param {string} namespace - The name of the namespace.
1363
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1364
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1365
   */
1366
  getSubscriptionNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
×
UNCOV
1367
    return rclnodejs.getSubscriptionNamesAndTypesByNode(
×
1368
      this.handle,
1369
      nodeName,
1370
      namespace,
1371
      noDemangle
1372
    );
1373
  }
1374

1375
  /**
1376
   * Get service names and types for which a remote node has servers.
1377
   * @param {string} nodeName - The name of the node.
1378
   * @param {string} namespace - The name of the namespace.
1379
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1380
   */
1381
  getServiceNamesAndTypesByNode(nodeName, namespace) {
UNCOV
1382
    return rclnodejs.getServiceNamesAndTypesByNode(
×
1383
      this.handle,
1384
      nodeName,
1385
      namespace
1386
    );
1387
  }
1388

1389
  /**
1390
   * Get service names and types for which a remote node has clients.
1391
   * @param {string} nodeName - The name of the node.
1392
   * @param {string} namespace - The name of the namespace.
1393
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1394
   */
1395
  getClientNamesAndTypesByNode(nodeName, namespace) {
UNCOV
1396
    return rclnodejs.getClientNamesAndTypesByNode(
×
1397
      this.handle,
1398
      nodeName,
1399
      namespace
1400
    );
1401
  }
1402

1403
  /**
1404
   * Get the list of topics discovered by the provided node.
1405
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
1406
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1407
   */
1408
  getTopicNamesAndTypes(noDemangle = false) {
×
UNCOV
1409
    return rclnodejs.getTopicNamesAndTypes(this.handle, noDemangle);
×
1410
  }
1411

1412
  /**
1413
   * Get the list of services discovered by the provided node.
1414
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
1415
   */
1416
  getServiceNamesAndTypes() {
1417
    return rclnodejs.getServiceNamesAndTypes(this.handle);
2✔
1418
  }
1419

1420
  /**
1421
   * Return a list of publishers on a given topic.
1422
   *
1423
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
1424
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
1425
   *
1426
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
1427
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1428
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
1429
   * follow ROS topic name conventions.
1430
   *
1431
   * `topic` may be a relative, private, or fully qualified topic name.
1432
   *  A relative or private topic will be expanded using this node's namespace and name.
1433
   *  The queried `topic` is not remapped.
1434
   *
1435
   * @param {string} topic - The topic on which to find the publishers.
1436
   * @param {boolean} [noDemangle=false] - If `true`, `topic` needs to be a valid middleware topic
1437
   *                               name, otherwise it should be a valid ROS topic name. Defaults to `false`.
1438
   * @returns {Array} - list of publishers
1439
   */
1440
  getPublishersInfoByTopic(topic, noDemangle = false) {
1✔
1441
    return rclnodejs.getPublishersInfoByTopic(
4✔
1442
      this.handle,
1443
      this._getValidatedTopic(topic, noDemangle),
1444
      noDemangle
1445
    );
1446
  }
1447

1448
  /**
1449
   * Return a list of subscriptions on a given topic.
1450
   *
1451
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
1452
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
1453
   *
1454
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
1455
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1456
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
1457
   * follow ROS topic name conventions.
1458
   *
1459
   * `topic` may be a relative, private, or fully qualified topic name.
1460
   *  A relative or private topic will be expanded using this node's namespace and name.
1461
   *  The queried `topic` is not remapped.
1462
   *
1463
   * @param {string} topic - The topic on which to find the subscriptions.
1464
   * @param {boolean} [noDemangle=false] -  If `true`, `topic` needs to be a valid middleware topic
1465
                                    name, otherwise it should be a valid ROS topic name. Defaults to `false`.
1466
   * @returns {Array} - list of subscriptions
1467
   */
1468
  getSubscriptionsInfoByTopic(topic, noDemangle = false) {
×
1469
    return rclnodejs.getSubscriptionsInfoByTopic(
2✔
1470
      this.handle,
1471
      this._getValidatedTopic(topic, noDemangle),
1472
      noDemangle
1473
    );
1474
  }
1475

1476
  /**
1477
   * Return a list of clients on a given service.
1478
   *
1479
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
1480
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
1481
   *
1482
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
1483
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1484
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
1485
   * follow ROS service name conventions.
1486
   *
1487
   * `service` may be a relative, private, or fully qualified service name.
1488
   *  A relative or private service will be expanded using this node's namespace and name.
1489
   *  The queried `service` is not remapped.
1490
   *
1491
   * @param {string} service - The service on which to find the clients.
1492
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
1493
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
1494
   * @returns {Array} - list of clients
1495
   */
1496
  getClientsInfoByService(service, noDemangle = false) {
×
1497
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.ROLLING) {
2!
UNCOV
1498
      console.warn(
×
1499
        'getClientsInfoByService is not supported by this version of ROS 2'
1500
      );
UNCOV
1501
      return null;
×
1502
    }
1503
    return rclnodejs.getClientsInfoByService(
2✔
1504
      this.handle,
1505
      this._getValidatedServiceName(service, noDemangle),
1506
      noDemangle
1507
    );
1508
  }
1509

1510
  /**
1511
   * Return a list of servers on a given service.
1512
   *
1513
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
1514
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
1515
   *
1516
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
1517
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
1518
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
1519
   * follow ROS service name conventions.
1520
   *
1521
   * `service` may be a relative, private, or fully qualified service name.
1522
   *  A relative or private service will be expanded using this node's namespace and name.
1523
   *  The queried `service` is not remapped.
1524
   *
1525
   * @param {string} service - The service on which to find the servers.
1526
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
1527
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
1528
   * @returns {Array} - list of servers
1529
   */
1530
  getServersInfoByService(service, noDemangle = false) {
×
1531
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.ROLLING) {
2!
UNCOV
1532
      console.warn(
×
1533
        'getServersInfoByService is not supported by this version of ROS 2'
1534
      );
UNCOV
1535
      return null;
×
1536
    }
1537
    return rclnodejs.getServersInfoByService(
2✔
1538
      this.handle,
1539
      this._getValidatedServiceName(service, noDemangle),
1540
      noDemangle
1541
    );
1542
  }
1543

1544
  /**
1545
   * Get the list of nodes discovered by the provided node.
1546
   * @return {Array<string>} - An array of the names.
1547
   */
1548
  getNodeNames() {
1549
    return this.getNodeNamesAndNamespaces().map((item) => item.name);
41✔
1550
  }
1551

1552
  /**
1553
   * Get the list of nodes and their namespaces discovered by the provided node.
1554
   * @return {Array<{name: string, namespace: string}>} An array of the names and namespaces.
1555
   */
1556
  getNodeNamesAndNamespaces() {
1557
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ false);
17✔
1558
  }
1559

1560
  /**
1561
   * Get the list of nodes and their namespaces with enclaves discovered by the provided node.
1562
   * @return {Array<{name: string, namespace: string, enclave: string}>} An array of the names, namespaces and enclaves.
1563
   */
1564
  getNodeNamesAndNamespacesWithEnclaves() {
1565
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ true);
1✔
1566
  }
1567

1568
  /**
1569
   * Return the number of publishers on a given topic.
1570
   * @param {string} topic - The name of the topic.
1571
   * @returns {number} - Number of publishers on the given topic.
1572
   */
1573
  countPublishers(topic) {
1574
    let expandedTopic = rclnodejs.expandTopicName(
6✔
1575
      topic,
1576
      this.name(),
1577
      this.namespace()
1578
    );
1579
    rclnodejs.validateTopicName(expandedTopic);
6✔
1580

1581
    return rclnodejs.countPublishers(this.handle, expandedTopic);
6✔
1582
  }
1583

1584
  /**
1585
   * Return the number of subscribers on a given topic.
1586
   * @param {string} topic - The name of the topic.
1587
   * @returns {number} - Number of subscribers on the given topic.
1588
   */
1589
  countSubscribers(topic) {
1590
    let expandedTopic = rclnodejs.expandTopicName(
6✔
1591
      topic,
1592
      this.name(),
1593
      this.namespace()
1594
    );
1595
    rclnodejs.validateTopicName(expandedTopic);
6✔
1596

1597
    return rclnodejs.countSubscribers(this.handle, expandedTopic);
6✔
1598
  }
1599

1600
  /**
1601
   * Get the number of clients on a given service name.
1602
   * @param {string} serviceName - the service name
1603
   * @returns {Number}
1604
   */
1605
  countClients(serviceName) {
1606
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
2!
UNCOV
1607
      console.warn('countClients is not supported by this version of ROS 2');
×
UNCOV
1608
      return null;
×
1609
    }
1610
    return rclnodejs.countClients(this.handle, serviceName);
2✔
1611
  }
1612

1613
  /**
1614
   * Get the number of services on a given service name.
1615
   * @param {string} serviceName - the service name
1616
   * @returns {Number}
1617
   */
1618
  countServices(serviceName) {
1619
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
1!
UNCOV
1620
      console.warn('countServices is not supported by this version of ROS 2');
×
UNCOV
1621
      return null;
×
1622
    }
1623
    return rclnodejs.countServices(this.handle, serviceName);
1✔
1624
  }
1625

1626
  /**
1627
   * Get the list of parameter-overrides found on the commandline and
1628
   * in the NodeOptions.parameter_overrides property.
1629
   *
1630
   * @return {Array<Parameter>} - An array of Parameters.
1631
   */
1632
  getParameterOverrides() {
1633
    return Array.from(this._parameterOverrides.values());
8✔
1634
  }
1635

1636
  /**
1637
   * Declare a parameter.
1638
   *
1639
   * Internally, register a parameter and it's descriptor.
1640
   * If a parameter-override exists, it's value will replace that of the parameter
1641
   * unless ignoreOverride is true.
1642
   * If the descriptor is undefined, then a ParameterDescriptor will be inferred
1643
   * from the parameter's state.
1644
   *
1645
   * If a parameter by the same name has already been declared then an Error is thrown.
1646
   * A parameter must be undeclared before attempting to redeclare it.
1647
   *
1648
   * @param {Parameter} parameter - Parameter to declare.
1649
   * @param {ParameterDescriptor} [descriptor] - Optional descriptor for parameter.
1650
   * @param {boolean} [ignoreOverride] - When true disregard any parameter-override that may be present.
1651
   * @return {Parameter} - The newly declared parameter.
1652
   */
1653
  declareParameter(parameter, descriptor, ignoreOverride = false) {
2,364✔
1654
    const parameters = this.declareParameters(
2,365✔
1655
      [parameter],
1656
      descriptor ? [descriptor] : [],
2,365✔
1657
      ignoreOverride
1658
    );
1659
    return parameters.length == 1 ? parameters[0] : null;
2,365!
1660
  }
1661

1662
  /**
1663
   * Declare a list of parameters.
1664
   *
1665
   * Internally register parameters with their corresponding descriptor one by one
1666
   * in the order they are provided. This is an atomic operation. If an error
1667
   * occurs the process halts and no further parameters are declared.
1668
   * Parameters that have already been processed are undeclared.
1669
   *
1670
   * While descriptors is an optional parameter, when provided there must be
1671
   * a descriptor for each parameter; otherwise an Error is thrown.
1672
   * If descriptors is not provided then a descriptor will be inferred
1673
   * from each parameter's state.
1674
   *
1675
   * When a parameter-override is available, the parameter's value
1676
   * will be replaced with that of the parameter-override unless ignoreOverrides
1677
   * is true.
1678
   *
1679
   * If a parameter by the same name has already been declared then an Error is thrown.
1680
   * A parameter must be undeclared before attempting to redeclare it.
1681
   *
1682
   * Prior to declaring the parameters each SetParameterEventCallback registered
1683
   * using setOnParameterEventCallback() is called in succession with the parameters
1684
   * list. Any SetParameterEventCallback that retuns does not return a successful
1685
   * result will cause the entire operation to terminate with no changes to the
1686
   * parameters. When all SetParameterEventCallbacks return successful then the
1687
   * list of parameters is updated.
1688
   *
1689
   * @param {Parameter[]} parameters - The parameters to declare.
1690
   * @param {ParameterDescriptor[]} [descriptors] - Optional descriptors,
1691
   *    a 1-1 correspondence with parameters.
1692
   * @param {boolean} ignoreOverrides - When true, parameter-overrides are
1693
   *    not considered, i.e.,ignored.
1694
   * @return {Parameter[]} - The declared parameters.
1695
   */
1696
  declareParameters(parameters, descriptors = [], ignoreOverrides = false) {
×
1697
    if (!Array.isArray(parameters)) {
2,365!
UNCOV
1698
      throw new TypeValidationError('parameters', parameters, 'Array', {
×
1699
        nodeName: this.name(),
1700
      });
1701
    }
1702
    if (!Array.isArray(descriptors)) {
2,365!
UNCOV
1703
      throw new TypeValidationError('descriptors', descriptors, 'Array', {
×
1704
        nodeName: this.name(),
1705
      });
1706
    }
1707
    if (descriptors.length > 0 && parameters.length !== descriptors.length) {
2,365!
UNCOV
1708
      throw new ValidationError(
×
1709
        'Each parameter must have a corresponding ParameterDescriptor',
1710
        {
1711
          code: 'PARAMETER_DESCRIPTOR_MISMATCH',
1712
          argumentName: 'descriptors',
1713
          providedValue: descriptors.length,
1714
          expectedType: `Array with length ${parameters.length}`,
1715
          nodeName: this.name(),
1716
        }
1717
      );
1718
    }
1719

1720
    const declaredDescriptors = [];
2,365✔
1721
    const declaredParameters = [];
2,365✔
1722
    const declaredParameterCollisions = [];
2,365✔
1723
    for (let i = 0; i < parameters.length; i++) {
2,365✔
1724
      let parameter =
1725
        !ignoreOverrides && this._parameterOverrides.has(parameters[i].name)
2,365✔
1726
          ? this._parameterOverrides.get(parameters[i].name)
1727
          : parameters[i];
1728

1729
      // stop processing parameters that have already been declared
1730
      if (this._parameters.has(parameter.name)) {
2,365!
UNCOV
1731
        declaredParameterCollisions.push(parameter);
×
UNCOV
1732
        continue;
×
1733
      }
1734

1735
      // create descriptor for parameter if not provided
1736
      let descriptor =
1737
        descriptors.length > 0
2,365✔
1738
          ? descriptors[i]
1739
          : ParameterDescriptor.fromParameter(parameter);
1740

1741
      descriptor.validate();
2,365✔
1742

1743
      declaredDescriptors.push(descriptor);
2,365✔
1744
      declaredParameters.push(parameter);
2,365✔
1745
    }
1746

1747
    if (declaredParameterCollisions.length > 0) {
2,365!
1748
      const errorMsg =
UNCOV
1749
        declaredParameterCollisions.length == 1
×
1750
          ? `Parameter(${declaredParameterCollisions[0]}) already declared.`
1751
          : `Multiple parameters already declared, e.g., Parameter(${declaredParameterCollisions[0]}).`;
UNCOV
1752
      throw new Error(errorMsg);
×
1753
    }
1754

1755
    // register descriptor
1756
    for (const descriptor of declaredDescriptors) {
2,365✔
1757
      this._parameterDescriptors.set(descriptor.name, descriptor);
2,365✔
1758
    }
1759

1760
    const result = this._setParametersAtomically(declaredParameters, true);
2,365✔
1761
    if (!result.successful) {
2,365!
1762
      // unregister descriptors
UNCOV
1763
      for (const descriptor of declaredDescriptors) {
×
UNCOV
1764
        this._parameterDescriptors.delete(descriptor.name);
×
1765
      }
1766

UNCOV
1767
      throw new Error(result.reason);
×
1768
    }
1769

1770
    return this.getParameters(declaredParameters.map((param) => param.name));
2,365✔
1771
  }
1772

1773
  /**
1774
   * Undeclare a parameter.
1775
   *
1776
   * Readonly parameters can not be undeclared or updated.
1777
   * @param {string} name - Name of parameter to undeclare.
1778
   * @return {undefined} -
1779
   */
1780
  undeclareParameter(name) {
1781
    if (!this.hasParameter(name)) return;
1!
1782

1783
    const descriptor = this.getParameterDescriptor(name);
1✔
1784
    if (descriptor.readOnly) {
1!
UNCOV
1785
      throw new Error(
×
1786
        `${name} parameter is read-only and can not be undeclared`
1787
      );
1788
    }
1789

1790
    this._parameters.delete(name);
1✔
1791
    this._parameterDescriptors.delete(name);
1✔
1792
  }
1793

1794
  /**
1795
   * Determine if a parameter has been declared.
1796
   * @param {string} name - name of parameter
1797
   * @returns {boolean} - Return true if parameter is declared; false otherwise.
1798
   */
1799
  hasParameter(name) {
1800
    return this._parameters.has(name);
5,911✔
1801
  }
1802

1803
  /**
1804
   * Get a declared parameter by name.
1805
   *
1806
   * If unable to locate a declared parameter then a
1807
   * parameter with type == PARAMETER_NOT_SET is returned.
1808
   *
1809
   * @param {string} name - The name of the parameter.
1810
   * @return {Parameter} - The parameter.
1811
   */
1812
  getParameter(name) {
1813
    return this.getParameters([name])[0];
1,758✔
1814
  }
1815

1816
  /**
1817
   * Get a list of parameters.
1818
   *
1819
   * Find and return the declared parameters.
1820
   * If no names are provided return all declared parameters.
1821
   *
1822
   * If unable to locate a declared parameter then a
1823
   * parameter with type == PARAMETER_NOT_SET is returned in
1824
   * it's place.
1825
   *
1826
   * @param {string[]} [names] - The names of the declared parameters
1827
   *    to find or null indicating to return all declared parameters.
1828
   * @return {Parameter[]} - The parameters.
1829
   */
1830
  getParameters(names = []) {
12✔
1831
    let params = [];
4,161✔
1832

1833
    if (names.length == 0) {
4,161✔
1834
      // get all parameters
1835
      params = [...this._parameters.values()];
12✔
1836
      return params;
12✔
1837
    }
1838

1839
    for (const name of names) {
4,149✔
1840
      const param = this.hasParameter(name)
4,156✔
1841
        ? this._parameters.get(name)
1842
        : new Parameter(name, ParameterType.PARAMETER_NOT_SET);
1843

1844
      params.push(param);
4,156✔
1845
    }
1846

1847
    return params;
4,149✔
1848
  }
1849

1850
  /**
1851
   * Get the types of given parameters.
1852
   *
1853
   * Return the types of given parameters.
1854
   *
1855
   * @param {string[]} [names] - The names of the declared parameters.
1856
   * @return {Uint8Array} - The types.
1857
   */
1858
  getParameterTypes(names = []) {
×
1859
    let types = [];
3✔
1860

1861
    for (const name of names) {
3✔
1862
      const descriptor = this._parameterDescriptors.get(name);
7✔
1863
      if (descriptor) {
7!
1864
        types.push(descriptor.type);
7✔
1865
      }
1866
    }
1867
    return types;
3✔
1868
  }
1869

1870
  /**
1871
   * Get the names of all declared parameters.
1872
   *
1873
   * @return {Array<string>} - The declared parameter names or empty array if
1874
   *    no parameters have been declared.
1875
   */
1876
  getParameterNames() {
1877
    return this.getParameters().map((param) => param.name);
53✔
1878
  }
1879

1880
  /**
1881
   * Determine if a parameter descriptor exists.
1882
   *
1883
   * @param {string} name - The name of a descriptor to for.
1884
   * @return {boolean} - true if a descriptor has been declared; otherwise false.
1885
   */
1886
  hasParameterDescriptor(name) {
1887
    return !!this.getParameterDescriptor(name);
2,395✔
1888
  }
1889

1890
  /**
1891
   * Get a declared parameter descriptor by name.
1892
   *
1893
   * If unable to locate a declared parameter descriptor then a
1894
   * descriptor with type == PARAMETER_NOT_SET is returned.
1895
   *
1896
   * @param {string} name - The name of the parameter descriptor to find.
1897
   * @return {ParameterDescriptor} - The parameter descriptor.
1898
   */
1899
  getParameterDescriptor(name) {
1900
    return this.getParameterDescriptors([name])[0];
4,791✔
1901
  }
1902

1903
  /**
1904
   * Find a list of declared ParameterDescriptors.
1905
   *
1906
   * If no names are provided return all declared descriptors.
1907
   *
1908
   * If unable to locate a declared descriptor then a
1909
   * descriptor with type == PARAMETER_NOT_SET is returned in
1910
   * it's place.
1911
   *
1912
   * @param {string[]} [names] - The names of the declared parameter
1913
   *    descriptors to find or null indicating to return all declared descriptors.
1914
   * @return {ParameterDescriptor[]} - The parameter descriptors.
1915
   */
1916
  getParameterDescriptors(names = []) {
×
1917
    let descriptors = [];
4,794✔
1918

1919
    if (names.length == 0) {
4,794!
1920
      // get all parameters
UNCOV
1921
      descriptors = [...this._parameterDescriptors.values()];
×
UNCOV
1922
      return descriptors;
×
1923
    }
1924

1925
    for (const name of names) {
4,794✔
1926
      let descriptor = this._parameterDescriptors.get(name);
4,796✔
1927
      if (!descriptor) {
4,796!
UNCOV
1928
        descriptor = new ParameterDescriptor(
×
1929
          name,
1930
          ParameterType.PARAMETER_NOT_SET
1931
        );
1932
      }
1933
      descriptors.push(descriptor);
4,796✔
1934
    }
1935

1936
    return descriptors;
4,794✔
1937
  }
1938

1939
  /**
1940
   * Replace a declared parameter.
1941
   *
1942
   * The parameter being replaced must be a declared parameter who's descriptor
1943
   * is not readOnly; otherwise an Error is thrown.
1944
   *
1945
   * @param {Parameter} parameter - The new parameter.
1946
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - The result of the operation.
1947
   */
1948
  setParameter(parameter) {
1949
    const results = this.setParameters([parameter]);
15✔
1950
    return results[0];
15✔
1951
  }
1952

1953
  /**
1954
   * Replace a list of declared parameters.
1955
   *
1956
   * Declared parameters are replaced in the order they are provided and
1957
   * a ParameterEvent is published for each individual parameter change.
1958
   *
1959
   * Prior to setting the parameters each SetParameterEventCallback registered
1960
   * using setOnParameterEventCallback() is called in succession with the parameters
1961
   * list. Any SetParameterEventCallback that retuns does not return a successful
1962
   * result will cause the entire operation to terminate with no changes to the
1963
   * parameters. When all SetParameterEventCallbacks return successful then the
1964
   * list of parameters is updated.
1965
   *
1966
   * If an error occurs, the process is stopped and returned. Parameters
1967
   * set before an error remain unchanged.
1968
   *
1969
   * @param {Parameter[]} parameters - The parameters to set.
1970
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult[]} - A list of SetParameterResult, one for each parameter that was set.
1971
   */
1972
  setParameters(parameters = []) {
×
1973
    return parameters.map((parameter) =>
26✔
1974
      this.setParametersAtomically([parameter])
29✔
1975
    );
1976
  }
1977

1978
  /**
1979
   * Repalce a list of declared parameters atomically.
1980
   *
1981
   * Declared parameters are replaced in the order they are provided.
1982
   * A single ParameterEvent is published collectively for all changed
1983
   * parameters.
1984
   *
1985
   * Prior to setting the parameters each SetParameterEventCallback registered
1986
   * using setOnParameterEventCallback() is called in succession with the parameters
1987
   * list. Any SetParameterEventCallback that retuns does not return a successful
1988
   * result will cause the entire operation to terminate with no changes to the
1989
   * parameters. When all SetParameterEventCallbacks return successful then the
1990
   * list of parameters is updated.d
1991
   *
1992
   * If an error occurs, the process stops immediately. All parameters updated to
1993
   * the point of the error are reverted to their previous state.
1994
   *
1995
   * @param {Parameter[]} parameters - The parameters to set.
1996
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - describes the result of setting 1 or more parameters.
1997
   */
1998
  setParametersAtomically(parameters = []) {
×
1999
    return this._setParametersAtomically(parameters);
30✔
2000
  }
2001

2002
  /**
2003
   * Internal method for updating parameters atomically.
2004
   *
2005
   * Prior to setting the parameters each SetParameterEventCallback registered
2006
   * using setOnParameterEventCallback() is called in succession with the parameters
2007
   * list. Any SetParameterEventCallback that retuns does not return a successful
2008
   * result will cause the entire operation to terminate with no changes to the
2009
   * parameters. When all SetParameterEventCallbacks return successful then the
2010
   * list of parameters is updated.
2011
   *
2012
   * @param {Paramerter[]} parameters - The parameters to update.
2013
   * @param {boolean} declareParameterMode - When true parameters are being declared;
2014
   *    otherwise they are being changed.
2015
   * @return {SetParameterResult} - A single collective result.
2016
   */
2017
  _setParametersAtomically(parameters = [], declareParameterMode = false) {
30!
2018
    let result = this._validateParameters(parameters, declareParameterMode);
2,395✔
2019
    if (!result.successful) {
2,395!
UNCOV
2020
      return result;
×
2021
    }
2022

2023
    // give all SetParametersCallbacks a chance to veto this change
2024
    for (const callback of this._setParametersCallbacks) {
2,395✔
2025
      result = callback(parameters);
1,533✔
2026
      if (!result.successful) {
1,533✔
2027
        // a callback has vetoed a parameter change
2028
        return result;
1✔
2029
      }
2030
    }
2031

2032
    // collectively track updates to parameters for use
2033
    // when publishing a ParameterEvent
2034
    const newParameters = [];
2,394✔
2035
    const changedParameters = [];
2,394✔
2036
    const deletedParameters = [];
2,394✔
2037

2038
    for (const parameter of parameters) {
2,394✔
2039
      if (parameter.type == ParameterType.PARAMETER_NOT_SET) {
2,394✔
2040
        this.undeclareParameter(parameter.name);
1✔
2041
        deletedParameters.push(parameter);
1✔
2042
      } else {
2043
        this._parameters.set(parameter.name, parameter);
2,393✔
2044
        if (declareParameterMode) {
2,393✔
2045
          newParameters.push(parameter);
2,365✔
2046
        } else {
2047
          changedParameters.push(parameter);
28✔
2048
        }
2049
      }
2050
    }
2051

2052
    // create ParameterEvent
2053
    const parameterEvent = new (loader.loadInterface(
2,394✔
2054
      PARAMETER_EVENT_MSG_TYPE
2055
    ))();
2056

2057
    const { seconds, nanoseconds } = this._clock.now().secondsAndNanoseconds;
2,394✔
2058
    parameterEvent.stamp = {
2,394✔
2059
      sec: Number(seconds),
2060
      nanosec: Number(nanoseconds),
2061
    };
2062

2063
    parameterEvent.node =
2,394✔
2064
      this.namespace() === '/'
2,394✔
2065
        ? this.namespace() + this.name()
2066
        : this.namespace() + '/' + this.name();
2067

2068
    if (newParameters.length > 0) {
2,394✔
2069
      parameterEvent['new_parameters'] = newParameters.map((parameter) =>
2,365✔
2070
        parameter.toParameterMessage()
2,365✔
2071
      );
2072
    }
2073
    if (changedParameters.length > 0) {
2,394✔
2074
      parameterEvent['changed_parameters'] = changedParameters.map(
28✔
2075
        (parameter) => parameter.toParameterMessage()
28✔
2076
      );
2077
    }
2078
    if (deletedParameters.length > 0) {
2,394✔
2079
      parameterEvent['deleted_parameters'] = deletedParameters.map(
1✔
2080
        (parameter) => parameter.toParameterMessage()
1✔
2081
      );
2082
    }
2083

2084
    // Publish ParameterEvent.
2085
    this._parameterEventPublisher.publish(parameterEvent);
2,394✔
2086

2087
    return {
2,394✔
2088
      successful: true,
2089
      reason: '',
2090
    };
2091
  }
2092

2093
  /**
2094
   * This callback is called when declaring a parameter or setting a parameter.
2095
   * The callback is provided a list of parameters and returns a SetParameterResult
2096
   * to indicate approval or veto of the operation.
2097
   *
2098
   * @callback SetParametersCallback
2099
   * @param {Parameter[]} parameters - The message published
2100
   * @returns {rcl_interfaces.msg.SetParameterResult} -
2101
   *
2102
   * @see [Node.addOnSetParametersCallback]{@link Node#addOnSetParametersCallback}
2103
   * @see [Node.removeOnSetParametersCallback]{@link Node#removeOnSetParametersCallback}
2104
   */
2105

2106
  /**
2107
   * Add a callback to the front of the list of callbacks invoked for parameter declaration
2108
   * and setting. No checks are made for duplicate callbacks.
2109
   *
2110
   * @param {SetParametersCallback} callback - The callback to add.
2111
   * @returns {undefined}
2112
   */
2113
  addOnSetParametersCallback(callback) {
2114
    this._setParametersCallbacks.unshift(callback);
886✔
2115
  }
2116

2117
  /**
2118
   * Remove a callback from the list of SetParametersCallbacks.
2119
   * If the callback is not found the process is a nop.
2120
   *
2121
   * @param {SetParametersCallback} callback - The callback to be removed
2122
   * @returns {undefined}
2123
   */
2124
  removeOnSetParametersCallback(callback) {
2125
    const idx = this._setParametersCallbacks.indexOf(callback);
2✔
2126
    if (idx > -1) {
2!
2127
      this._setParametersCallbacks.splice(idx, 1);
2✔
2128
    }
2129
  }
2130

2131
  /**
2132
   * Get the fully qualified name of the node.
2133
   *
2134
   * @returns {string} - String containing the fully qualified name of the node.
2135
   */
2136
  getFullyQualifiedName() {
2137
    return rclnodejs.getFullyQualifiedName(this.handle);
1✔
2138
  }
2139

2140
  /**
2141
   * Get the RMW implementation identifier
2142
   * @returns {string} - The RMW implementation identifier.
2143
   */
2144
  getRMWImplementationIdentifier() {
2145
    return rclnodejs.getRMWImplementationIdentifier();
1✔
2146
  }
2147

2148
  /**
2149
   * Return a topic name expanded and remapped.
2150
   * @param {string} topicName - Topic name to be expanded and remapped.
2151
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2152
   * @returns {string} - A fully qualified topic name.
2153
   */
2154
  resolveTopicName(topicName, onlyExpand = false) {
2✔
2155
    if (typeof topicName !== 'string') {
3!
UNCOV
2156
      throw new TypeValidationError('topicName', topicName, 'string', {
×
2157
        nodeName: this.name(),
2158
      });
2159
    }
2160
    return rclnodejs.resolveName(
3✔
2161
      this.handle,
2162
      topicName,
2163
      onlyExpand,
2164
      /*isService=*/ false
2165
    );
2166
  }
2167

2168
  /**
2169
   * Return a service name expanded and remapped.
2170
   * @param {string} service - Service name to be expanded and remapped.
2171
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2172
   * @returns {string} - A fully qualified service name.
2173
   */
2174
  resolveServiceName(service, onlyExpand = false) {
6✔
2175
    if (typeof service !== 'string') {
7!
UNCOV
2176
      throw new TypeValidationError('service', service, 'string', {
×
2177
        nodeName: this.name(),
2178
      });
2179
    }
2180
    return rclnodejs.resolveName(
7✔
2181
      this.handle,
2182
      service,
2183
      onlyExpand,
2184
      /*isService=*/ true
2185
    );
2186
  }
2187

2188
  // returns on 1st error or result {successful, reason}
2189
  _validateParameters(parameters = [], declareParameterMode = false) {
×
2190
    for (const parameter of parameters) {
2,395✔
2191
      // detect invalid parameter
2192
      try {
2,395✔
2193
        parameter.validate();
2,395✔
2194
      } catch {
UNCOV
2195
        return {
×
2196
          successful: false,
2197
          reason: `Invalid ${parameter.name}`,
2198
        };
2199
      }
2200

2201
      // detect undeclared parameter
2202
      if (!this.hasParameterDescriptor(parameter.name)) {
2,395!
UNCOV
2203
        return {
×
2204
          successful: false,
2205
          reason: `Parameter ${parameter.name} has not been declared`,
2206
        };
2207
      }
2208

2209
      // detect readonly parameter that can not be updated
2210
      const descriptor = this.getParameterDescriptor(parameter.name);
2,395✔
2211
      if (!declareParameterMode && descriptor.readOnly) {
2,395!
UNCOV
2212
        return {
×
2213
          successful: false,
2214
          reason: `Parameter ${parameter.name} is readonly`,
2215
        };
2216
      }
2217

2218
      // validate parameter against descriptor if not an undeclare action
2219
      if (parameter.type != ParameterType.PARAMETER_NOT_SET) {
2,395✔
2220
        try {
2,394✔
2221
          descriptor.validateParameter(parameter);
2,394✔
2222
        } catch {
UNCOV
2223
          return {
×
2224
            successful: false,
2225
            reason: `Parameter ${parameter.name} does not  readonly`,
2226
          };
2227
        }
2228
      }
2229
    }
2230

2231
    return {
2,395✔
2232
      successful: true,
2233
      reason: null,
2234
    };
2235
  }
2236

2237
  // Get a Map(nodeName->Parameter[]) of CLI parameter args that
2238
  // apply to 'this' node, .e.g., -p mynode:foo:=bar -p hello:=world
2239
  _getNativeParameterOverrides() {
2240
    const overrides = new Map();
869✔
2241

2242
    // Get native parameters from rcl context->global_arguments.
2243
    // rclnodejs returns an array of objects, 1 for each node e.g., -p my_node:foo:=bar,
2244
    // and a node named '/**' for global parameter rules,
2245
    // i.e., does not include a node identifier, e.g., -p color:=red
2246
    // {
2247
    //   name: string // node name
2248
    //   parameters[] = {
2249
    //     name: string
2250
    //     type: uint
2251
    //     value: object
2252
    // }
2253
    const cliParamOverrideData = rclnodejs.getParameterOverrides(
869✔
2254
      this.context.handle
2255
    );
2256

2257
    // convert native CLI parameterOverrides to Map<nodeName,Array<ParameterOverride>>
2258
    const cliParamOverrides = new Map();
869✔
2259
    if (cliParamOverrideData) {
869✔
2260
      for (let nodeParamData of cliParamOverrideData) {
8✔
2261
        const nodeName = nodeParamData.name;
12✔
2262
        const nodeParamOverrides = [];
12✔
2263
        for (let paramData of nodeParamData.parameters) {
12✔
2264
          const paramOverride = new Parameter(
17✔
2265
            paramData.name,
2266
            paramData.type,
2267
            paramData.value
2268
          );
2269
          nodeParamOverrides.push(paramOverride);
17✔
2270
        }
2271
        cliParamOverrides.set(nodeName, nodeParamOverrides);
12✔
2272
      }
2273
    }
2274

2275
    // collect global CLI global parameters, name == /**
2276
    let paramOverrides = cliParamOverrides.get('/**'); // array of ParameterOverrides
869✔
2277
    if (paramOverrides) {
869✔
2278
      for (const parameter of paramOverrides) {
5✔
2279
        overrides.set(parameter.name, parameter);
6✔
2280
      }
2281
    }
2282

2283
    // merge CLI node parameterOverrides with global parameterOverrides, replace existing
2284
    paramOverrides = cliParamOverrides.get(this.name()); // array of ParameterOverrides
869✔
2285
    if (paramOverrides) {
869✔
2286
      for (const parameter of paramOverrides) {
5✔
2287
        overrides.set(parameter.name, parameter);
7✔
2288
      }
2289
    }
2290

2291
    return overrides;
869✔
2292
  }
2293

2294
  /**
2295
   * Invokes the callback with a raw message of the given type. After the callback completes
2296
   * the message will be destroyed.
2297
   * @param {function} Type - Message type to create.
2298
   * @param {function} callback - Callback to invoke. First parameter will be the raw message,
2299
   * and the second is a function to retrieve the deserialized message.
2300
   * @returns {undefined}
2301
   */
2302
  _runWithMessageType(Type, callback) {
2303
    let message = new Type();
1,029✔
2304

2305
    callback(message.toRawROS(), () => {
1,029✔
2306
      let result = new Type();
705✔
2307
      result.deserialize(message.refObject);
705✔
2308

2309
      return result;
705✔
2310
    });
2311

2312
    Type.destroyRawROS(message);
1,029✔
2313
  }
2314

2315
  _addActionClient(actionClient) {
2316
    this._actionClients.push(actionClient);
41✔
2317
    this.syncHandles();
41✔
2318
  }
2319

2320
  _addActionServer(actionServer) {
2321
    this._actionServers.push(actionServer);
41✔
2322
    this.syncHandles();
41✔
2323
  }
2324

2325
  _getValidatedTopic(topicName, noDemangle) {
2326
    if (noDemangle) {
6!
UNCOV
2327
      return topicName;
×
2328
    }
2329
    const fqTopicName = rclnodejs.expandTopicName(
6✔
2330
      topicName,
2331
      this.name(),
2332
      this.namespace()
2333
    );
2334
    validateFullTopicName(fqTopicName);
6✔
2335
    return rclnodejs.remapTopicName(this.handle, fqTopicName);
6✔
2336
  }
2337

2338
  _getValidatedServiceName(serviceName, noDemangle) {
2339
    if (typeof serviceName !== 'string') {
4!
UNCOV
2340
      throw new TypeValidationError('serviceName', serviceName, 'string', {
×
2341
        nodeName: this.name(),
2342
      });
2343
    }
2344

2345
    if (noDemangle) {
4!
UNCOV
2346
      return serviceName;
×
2347
    }
2348

2349
    const resolvedServiceName = this.resolveServiceName(serviceName);
4✔
2350
    rclnodejs.validateTopicName(resolvedServiceName);
4✔
2351
    return resolvedServiceName;
4✔
2352
  }
2353
}
2354

2355
/**
2356
 * Create an Options instance initialized with default values.
2357
 * @returns {Options} - The new initialized instance.
2358
 * @static
2359
 * @example
2360
 * {
2361
 *   enableTypedArray: true,
2362
 *   isRaw: false,
2363
 *   qos: QoS.profileDefault,
2364
 *   contentFilter: undefined,
2365
 *   serializationMode: 'default',
2366
 * }
2367
 */
2368
Node.getDefaultOptions = function () {
26✔
2369
  return {
8,023✔
2370
    enableTypedArray: true,
2371
    isRaw: false,
2372
    qos: QoS.profileDefault,
2373
    contentFilter: undefined,
2374
    serializationMode: 'default',
2375
  };
2376
};
2377

2378
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