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

RobotWebTools / rclnodejs / 23891445057

02 Apr 2026 08:27AM UTC coverage: 85.835% (+0.5%) from 85.297%
23891445057

Pull #1470

github

web-flow
Merge 0f72aa57f into bd80eec87
Pull Request #1470: Add pre-set and post-set parameter callbacks

1491 of 1893 branches covered (78.76%)

Branch coverage included in aggregate %.

23 of 24 new or added lines in 1 file covered. (95.83%)

55 existing lines in 1 file now uncovered.

3078 of 3430 relevant lines covered (89.74%)

448.8 hits per line

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

86.83
/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 = '',
45✔
80
    context = Context.defaultContext(),
82✔
81
    options = NodeOptions.defaultOptions,
82✔
82
    args = [],
103✔
83
    useGlobalArguments = true
103✔
84
  ) {
85
    super();
924✔
86

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

94
    this._init(nodeName, namespace, options, context, args, useGlobalArguments);
902✔
95
    debug(
891✔
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) {
902✔
104
      return options;
900✔
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);
902✔
125

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

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

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

167
    if (this._enableRosout) {
892✔
168
      rclnodejs.initRosoutPublisherForNode(this.handle);
890✔
169
    }
170

171
    this._parameterEventPublisher = this.createPublisher(
892✔
172
      PARAMETER_EVENT_MSG_TYPE,
173
      PARAMETER_EVENT_TOPIC
174
    );
175

176
    // initialize _parameterOverrides from parameters defined on the commandline
177
    this._parameterOverrides = this._getNativeParameterOverrides();
892✔
178

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

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

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

213
    if (options.startParameterServices) {
891✔
214
      this._parameterService = new ParameterService(this);
885✔
215
      this._parameterService.start();
885✔
216
    }
217

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

227
  execute(handles) {
228
    let timersReady = this._timers.filter((timer) =>
4,628✔
229
      handles.includes(timer.handle)
3,839✔
230
    );
231
    let guardsReady = this._guards.filter((guard) =>
4,628✔
232
      handles.includes(guard.handle)
3✔
233
    );
234
    let subscriptionsReady = this._subscriptions.filter((subscription) =>
4,628✔
235
      handles.includes(subscription.handle)
417✔
236
    );
237
    let clientsReady = this._clients.filter((client) =>
4,628✔
238
      handles.includes(client.handle)
172✔
239
    );
240
    let servicesReady = this._services.filter((service) =>
4,628✔
241
      handles.includes(service.handle)
14,497✔
242
    );
243
    let actionClientsReady = this._actionClients.filter((actionClient) =>
4,628✔
244
      handles.includes(actionClient.handle)
203✔
245
    );
246
    let actionServersReady = this._actionServers.filter((actionServer) =>
4,628✔
247
      handles.includes(actionServer.handle)
201✔
248
    );
249
    let eventsReady = this._events.filter((event) =>
4,628✔
250
      handles.includes(event.handle)
4✔
251
    );
252

253
    timersReady.forEach((timer) => {
4,628✔
254
      if (timer.isReady()) {
3,829!
255
        rclnodejs.callTimer(timer.handle);
3,829✔
256
        timer.callback();
3,829✔
257
      }
258
    });
259

260
    eventsReady.forEach((event) => {
4,628✔
261
      event.takeData();
4✔
262
    });
263

264
    for (const subscription of subscriptionsReady) {
4,628✔
265
      if (subscription.isDestroyed()) continue;
398✔
266
      if (subscription.isRaw) {
389✔
267
        let rawMessage = rclnodejs.rclTakeRaw(subscription.handle);
1✔
268
        if (rawMessage) {
1!
269
          subscription.processResponse(rawMessage);
1✔
270
        }
271
        continue;
1✔
272
      }
273

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

298
    for (const guard of guardsReady) {
4,628✔
299
      if (guard.isDestroyed()) continue;
3!
300

301
      guard.callback();
3✔
302
    }
303

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

320
    for (const service of servicesReady) {
4,628✔
321
      if (service.isDestroyed()) continue;
124!
322
      this._runWithMessageType(
124✔
323
        service.typeClass.Request,
324
        (message, deserialize) => {
325
          let header = rclnodejs.rclTakeRequest(
124✔
326
            service.handle,
327
            this.handle,
328
            message
329
          );
330
          if (header) {
124✔
331
            service.processRequest(header, deserialize());
91✔
332
          }
333
        }
334
      );
335
    }
336

337
    for (const actionClient of actionClientsReady) {
4,628✔
338
      if (actionClient.isDestroyed()) continue;
124!
339

340
      const properties = actionClient.handle.properties;
124✔
341

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

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

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

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

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

418
    for (const actionServer of actionServersReady) {
4,628✔
419
      if (actionServer.isDestroyed()) continue;
95!
420

421
      const properties = actionServer.handle.properties;
95✔
422

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

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

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

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

486
    // At this point it is safe to clear the cache of any
487
    // destroyed entity references
488
    Entity._gcHandles();
4,628✔
489
  }
490

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

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

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

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

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

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

557
  _removeEntityFromArray(entity, array) {
558
    let index = array.indexOf(entity);
391✔
559
    if (index > -1) {
391✔
560
      array.splice(index, 1);
389✔
561
    }
562
  }
563

564
  _destroyEntity(entity, array, syncHandles = true) {
336✔
565
    if (entity['isDestroyed'] && entity.isDestroyed()) return;
343✔
566

567
    this._removeEntityFromArray(entity, array);
335✔
568
    if (syncHandles) {
335✔
569
      this.syncHandles();
330✔
570
    }
571

572
    if (entity['_destroy']) {
335✔
573
      entity._destroy();
329✔
574
    } else {
575
      // guards and timers
576
      entity.handle.release();
6✔
577
    }
578
  }
579

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

590
    if (options === undefined) {
8,231✔
591
      return Node.getDefaultOptions();
8,197✔
592
    }
593

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

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

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

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

621
    return options;
33✔
622
  }
623

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

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

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

660
    return timer;
65✔
661
  }
662

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

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

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

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

698
    return rate;
7✔
699
  }
700

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

723
  _createPublisher(typeClass, topic, options, publisherClass, eventCallbacks) {
724
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
1,268✔
725
      typeClass = loader.loadInterface(typeClass);
1,244✔
726
    }
727
    options = this._validateOptions(options);
1,261✔
728

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

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

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

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

812
    if (typeof options === 'function') {
458✔
813
      callback = options;
343✔
814
      options = undefined;
343✔
815
    }
816
    options = this._validateOptions(options);
458✔
817

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

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

865
    return subscription;
427✔
866
  }
867

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

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

900
    observableSubscription = new ObservableSubscription(subscription);
7✔
901
    return observableSubscription;
7✔
902
  }
903

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

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

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

944
    return client;
159✔
945
  }
946

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

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

979
    if (typeof options === 'function') {
5,376✔
980
      callback = options;
5,353✔
981
      options = undefined;
5,353✔
982
    }
983
    options = this._validateOptions(options);
5,376✔
984

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

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

1016
    return service;
5,346✔
1017
  }
1018

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

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

1038
    return parameterClient;
103✔
1039
  }
1040

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

1062
    return watcher;
53✔
1063
  }
1064

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

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

1083
    return guard;
3✔
1084
  }
1085

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

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

1101
    this._parameterClients.forEach((paramClient) => paramClient.destroy());
915✔
1102
    this._parameterWatchers.forEach((watcher) => watcher.destroy());
915✔
1103
    this._parameterEventHandlers.forEach((handler) => handler.destroy());
915✔
1104

1105
    this.context.onNodeDestroyed(this);
915✔
1106

1107
    if (this._enableRosout) {
915✔
1108
      rclnodejs.finiRosoutPublisherForNode(this.handle);
890✔
1109
      this._enableRosout = false;
890✔
1110
    }
1111

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

1126
    if (this._rateTimerServer) {
915✔
1127
      this._rateTimerServer.shutdown();
5✔
1128
      this._rateTimerServer = null;
5✔
1129
    }
1130
  }
1131

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

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

1180
    this._destroyEntity(subscription, this._subscriptions);
107✔
1181
  }
1182

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1583
    return rclnodejs.countPublishers(this.handle, expandedTopic);
6✔
1584
  }
1585

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

1599
    return rclnodejs.countSubscribers(this.handle, expandedTopic);
6✔
1600
  }
1601

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

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

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

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

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

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

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

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

1743
      descriptor.validate();
2,422✔
1744

1745
      declaredDescriptors.push(descriptor);
2,422✔
1746
      declaredParameters.push(parameter);
2,422✔
1747
    }
1748

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

1757
    // register descriptor
1758
    for (const descriptor of declaredDescriptors) {
2,422✔
1759
      this._parameterDescriptors.set(descriptor.name, descriptor);
2,422✔
1760
    }
1761

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

UNCOV
1769
      throw new Error(result.reason);
×
1770
    }
1771

1772
    return this.getParameters(declaredParameters.map((param) => param.name));
2,422✔
1773
  }
1774

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

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

1792
    this._parameters.delete(name);
1✔
1793
    this._parameterDescriptors.delete(name);
1✔
1794
  }
1795

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

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

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

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

1841
    for (const name of names) {
4,256✔
1842
      const param = this.hasParameter(name)
4,263✔
1843
        ? this._parameters.get(name)
1844
        : new Parameter(name, ParameterType.PARAMETER_NOT_SET);
1845

1846
      params.push(param);
4,263✔
1847
    }
1848

1849
    return params;
4,256✔
1850
  }
1851

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

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

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

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

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

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

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

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

1938
    return descriptors;
4,926✔
1939
  }
1940

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

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

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

2004
  /**
2005
   * Internal method for updating parameters atomically.
2006
   *
2007
   * Prior to setting the parameters each SetParameterEventCallback registered
2008
   * using setOnParameterEventCallback() is called in succession with the parameters
2009
   * list. Any SetParameterEventCallback that retuns does not return a successful
2010
   * result will cause the entire operation to terminate with no changes to the
2011
   * parameters. When all SetParameterEventCallbacks return successful then the
2012
   * list of parameters is updated.
2013
   *
2014
   * @param {Paramerter[]} parameters - The parameters to update.
2015
   * @param {boolean} declareParameterMode - When true parameters are being declared;
2016
   *    otherwise they are being changed.
2017
   * @return {SetParameterResult} - A single collective result.
2018
   */
2019
  _setParametersAtomically(parameters = [], declareParameterMode = false) {
41!
2020
    // 1) PRE callbacks — pipeline: each callback receives the output of the previous
2021
    if (this._preSetParametersCallbacks.length > 0) {
2,463✔
2022
      for (const callback of this._preSetParametersCallbacks) {
6✔
2023
        const result = callback(parameters);
7✔
2024
        if (!Array.isArray(result)) {
7!
UNCOV
2025
          return {
×
2026
            successful: false,
2027
            reason:
2028
              'pre-set parameters callback must return an array of Parameters',
2029
          };
2030
        }
2031
        parameters = result;
7✔
2032
        if (parameters.length === 0) {
7✔
2033
          return {
2✔
2034
            successful: false,
2035
            reason:
2036
              'parameter list is empty after pre-set callback; set rejected',
2037
          };
2038
        }
2039
      }
2040
    }
2041

2042
    // 2) Validate
2043
    let result = this._validateParameters(parameters, declareParameterMode);
2,461✔
2044
    if (!result.successful) {
2,461!
UNCOV
2045
      return result;
×
2046
    }
2047

2048
    // give all SetParametersCallbacks a chance to veto this change
2049
    for (const callback of this._setParametersCallbacks) {
2,461✔
2050
      result = callback(parameters);
1,577✔
2051
      if (!result.successful) {
1,577✔
2052
        // a callback has vetoed a parameter change
2053
        return result;
3✔
2054
      }
2055
    }
2056

2057
    // collectively track updates to parameters for use
2058
    // when publishing a ParameterEvent
2059
    const newParameters = [];
2,458✔
2060
    const changedParameters = [];
2,458✔
2061
    const deletedParameters = [];
2,458✔
2062

2063
    for (const parameter of parameters) {
2,458✔
2064
      if (parameter.type == ParameterType.PARAMETER_NOT_SET) {
2,458✔
2065
        this.undeclareParameter(parameter.name);
1✔
2066
        deletedParameters.push(parameter);
1✔
2067
      } else {
2068
        this._parameters.set(parameter.name, parameter);
2,457✔
2069
        if (declareParameterMode) {
2,457✔
2070
          newParameters.push(parameter);
2,422✔
2071
        } else {
2072
          changedParameters.push(parameter);
35✔
2073
        }
2074
      }
2075
    }
2076

2077
    // create ParameterEvent
2078
    const parameterEvent = new (loader.loadInterface(
2,458✔
2079
      PARAMETER_EVENT_MSG_TYPE
2080
    ))();
2081

2082
    const { seconds, nanoseconds } = this._clock.now().secondsAndNanoseconds;
2,458✔
2083
    parameterEvent.stamp = {
2,458✔
2084
      sec: Number(seconds),
2085
      nanosec: Number(nanoseconds),
2086
    };
2087

2088
    parameterEvent.node =
2,458✔
2089
      this.namespace() === '/'
2,458✔
2090
        ? this.namespace() + this.name()
2091
        : this.namespace() + '/' + this.name();
2092

2093
    if (newParameters.length > 0) {
2,458✔
2094
      parameterEvent['new_parameters'] = newParameters.map((parameter) =>
2,422✔
2095
        parameter.toParameterMessage()
2,422✔
2096
      );
2097
    }
2098
    if (changedParameters.length > 0) {
2,458✔
2099
      parameterEvent['changed_parameters'] = changedParameters.map(
35✔
2100
        (parameter) => parameter.toParameterMessage()
35✔
2101
      );
2102
    }
2103
    if (deletedParameters.length > 0) {
2,458✔
2104
      parameterEvent['deleted_parameters'] = deletedParameters.map(
1✔
2105
        (parameter) => parameter.toParameterMessage()
1✔
2106
      );
2107
    }
2108

2109
    // Publish ParameterEvent.
2110
    this._parameterEventPublisher.publish(parameterEvent);
2,458✔
2111

2112
    // POST callbacks — for side effects after successful set
2113
    for (const callback of this._postSetParametersCallbacks) {
2,458✔
2114
      callback(parameters);
4✔
2115
    }
2116

2117
    return {
2,458✔
2118
      successful: true,
2119
      reason: '',
2120
    };
2121
  }
2122

2123
  /**
2124
   * This callback is called when declaring a parameter or setting a parameter.
2125
   * The callback is provided a list of parameters and returns a SetParameterResult
2126
   * to indicate approval or veto of the operation.
2127
   *
2128
   * @callback SetParametersCallback
2129
   * @param {Parameter[]} parameters - The message published
2130
   * @returns {rcl_interfaces.msg.SetParameterResult} -
2131
   *
2132
   * @see [Node.addOnSetParametersCallback]{@link Node#addOnSetParametersCallback}
2133
   * @see [Node.removeOnSetParametersCallback]{@link Node#removeOnSetParametersCallback}
2134
   */
2135

2136
  /**
2137
   * Add a callback to the front of the list of callbacks invoked for parameter declaration
2138
   * and setting. No checks are made for duplicate callbacks.
2139
   *
2140
   * @param {SetParametersCallback} callback - The callback to add.
2141
   * @returns {undefined}
2142
   */
2143
  addOnSetParametersCallback(callback) {
2144
    this._setParametersCallbacks.unshift(callback);
913✔
2145
  }
2146

2147
  /**
2148
   * Remove a callback from the list of SetParametersCallbacks.
2149
   * If the callback is not found the process is a nop.
2150
   *
2151
   * @param {SetParametersCallback} callback - The callback to be removed
2152
   * @returns {undefined}
2153
   */
2154
  removeOnSetParametersCallback(callback) {
2155
    const idx = this._setParametersCallbacks.indexOf(callback);
2✔
2156
    if (idx > -1) {
2!
2157
      this._setParametersCallbacks.splice(idx, 1);
2✔
2158
    }
2159
  }
2160

2161
  /**
2162
   * A callback invoked before parameter validation and setting.
2163
   * It receives the parameter list and must return a (possibly modified) parameter list.
2164
   *
2165
   * @callback PreSetParametersCallback
2166
   * @param {Parameter[]} parameters - The parameters about to be set.
2167
   * @returns {Parameter[]} - The modified parameter list to proceed with.
2168
   *
2169
   * @see [Node.addPreSetParametersCallback]{@link Node#addPreSetParametersCallback}
2170
   * @see [Node.removePreSetParametersCallback]{@link Node#removePreSetParametersCallback}
2171
   */
2172

2173
  /**
2174
   * Add a callback invoked before parameter validation.
2175
   * The callback receives the parameter list and must return a (possibly modified)
2176
   * parameter list. This can be used to coerce, add, or remove parameters before
2177
   * they are validated and applied. If any pre-set callback returns an empty list,
2178
   * the set is rejected.
2179
   *
2180
   * @param {PreSetParametersCallback} callback - The callback to add.
2181
   * @returns {undefined}
2182
   */
2183
  addPreSetParametersCallback(callback) {
2184
    this._preSetParametersCallbacks.unshift(callback);
8✔
2185
  }
2186

2187
  /**
2188
   * Remove a pre-set parameters callback.
2189
   *
2190
   * @param {PreSetParametersCallback} callback - The callback to remove.
2191
   * @returns {undefined}
2192
   */
2193
  removePreSetParametersCallback(callback) {
2194
    const idx = this._preSetParametersCallbacks.indexOf(callback);
1✔
2195
    if (idx > -1) {
1!
2196
      this._preSetParametersCallbacks.splice(idx, 1);
1✔
2197
    }
2198
  }
2199

2200
  /**
2201
   * A callback invoked after parameters have been successfully set.
2202
   * It receives the final parameter list. For side effects only (return value is ignored).
2203
   *
2204
   * @callback PostSetParametersCallback
2205
   * @param {Parameter[]} parameters - The parameters that were set.
2206
   * @returns {undefined}
2207
   *
2208
   * @see [Node.addPostSetParametersCallback]{@link Node#addPostSetParametersCallback}
2209
   * @see [Node.removePostSetParametersCallback]{@link Node#removePostSetParametersCallback}
2210
   */
2211

2212
  /**
2213
   * Add a callback invoked after parameters are successfully set.
2214
   * The callback receives the final parameter list. Useful for triggering
2215
   * side effects (e.g., reconfiguring a component when a parameter changes).
2216
   *
2217
   * @param {PostSetParametersCallback} callback - The callback to add.
2218
   * @returns {undefined}
2219
   */
2220
  addPostSetParametersCallback(callback) {
2221
    this._postSetParametersCallbacks.unshift(callback);
8✔
2222
  }
2223

2224
  /**
2225
   * Remove a post-set parameters callback.
2226
   *
2227
   * @param {PostSetParametersCallback} callback - The callback to remove.
2228
   * @returns {undefined}
2229
   */
2230
  removePostSetParametersCallback(callback) {
2231
    const idx = this._postSetParametersCallbacks.indexOf(callback);
1✔
2232
    if (idx > -1) {
1!
2233
      this._postSetParametersCallbacks.splice(idx, 1);
1✔
2234
    }
2235
  }
2236

2237
  /**
2238
   * Get the fully qualified name of the node.
2239
   *
2240
   * @returns {string} - String containing the fully qualified name of the node.
2241
   */
2242
  getFullyQualifiedName() {
2243
    return rclnodejs.getFullyQualifiedName(this.handle);
1✔
2244
  }
2245

2246
  /**
2247
   * Get the RMW implementation identifier
2248
   * @returns {string} - The RMW implementation identifier.
2249
   */
2250
  getRMWImplementationIdentifier() {
2251
    return rclnodejs.getRMWImplementationIdentifier();
1✔
2252
  }
2253

2254
  /**
2255
   * Return a topic name expanded and remapped.
2256
   * @param {string} topicName - Topic name to be expanded and remapped.
2257
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2258
   * @returns {string} - A fully qualified topic name.
2259
   */
2260
  resolveTopicName(topicName, onlyExpand = false) {
2✔
2261
    if (typeof topicName !== 'string') {
3!
NEW
2262
      throw new TypeValidationError('topicName', topicName, 'string', {
×
2263
        nodeName: this.name(),
2264
      });
2265
    }
2266
    return rclnodejs.resolveName(
3✔
2267
      this.handle,
2268
      topicName,
2269
      onlyExpand,
2270
      /*isService=*/ false
2271
    );
2272
  }
2273

2274
  /**
2275
   * Return a service name expanded and remapped.
2276
   * @param {string} service - Service name to be expanded and remapped.
2277
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
2278
   * @returns {string} - A fully qualified service name.
2279
   */
2280
  resolveServiceName(service, onlyExpand = false) {
6✔
2281
    if (typeof service !== 'string') {
7!
UNCOV
2282
      throw new TypeValidationError('service', service, 'string', {
×
2283
        nodeName: this.name(),
2284
      });
2285
    }
2286
    return rclnodejs.resolveName(
7✔
2287
      this.handle,
2288
      service,
2289
      onlyExpand,
2290
      /*isService=*/ true
2291
    );
2292
  }
2293

2294
  // returns on 1st error or result {successful, reason}
2295
  _validateParameters(parameters = [], declareParameterMode = false) {
×
2296
    for (const parameter of parameters) {
2,461✔
2297
      // detect invalid parameter
2298
      try {
2,461✔
2299
        parameter.validate();
2,461✔
2300
      } catch {
UNCOV
2301
        return {
×
2302
          successful: false,
2303
          reason: `Invalid ${parameter.name}`,
2304
        };
2305
      }
2306

2307
      // detect undeclared parameter
2308
      if (!this.hasParameterDescriptor(parameter.name)) {
2,461!
UNCOV
2309
        return {
×
2310
          successful: false,
2311
          reason: `Parameter ${parameter.name} has not been declared`,
2312
        };
2313
      }
2314

2315
      // detect readonly parameter that can not be updated
2316
      const descriptor = this.getParameterDescriptor(parameter.name);
2,461✔
2317
      if (!declareParameterMode && descriptor.readOnly) {
2,461!
UNCOV
2318
        return {
×
2319
          successful: false,
2320
          reason: `Parameter ${parameter.name} is readonly`,
2321
        };
2322
      }
2323

2324
      // validate parameter against descriptor if not an undeclare action
2325
      if (parameter.type != ParameterType.PARAMETER_NOT_SET) {
2,461✔
2326
        try {
2,460✔
2327
          descriptor.validateParameter(parameter);
2,460✔
2328
        } catch {
UNCOV
2329
          return {
×
2330
            successful: false,
2331
            reason: `Parameter ${parameter.name} does not  readonly`,
2332
          };
2333
        }
2334
      }
2335
    }
2336

2337
    return {
2,461✔
2338
      successful: true,
2339
      reason: null,
2340
    };
2341
  }
2342

2343
  // Get a Map(nodeName->Parameter[]) of CLI parameter args that
2344
  // apply to 'this' node, .e.g., -p mynode:foo:=bar -p hello:=world
2345
  _getNativeParameterOverrides() {
2346
    const overrides = new Map();
892✔
2347

2348
    // Get native parameters from rcl context->global_arguments.
2349
    // rclnodejs returns an array of objects, 1 for each node e.g., -p my_node:foo:=bar,
2350
    // and a node named '/**' for global parameter rules,
2351
    // i.e., does not include a node identifier, e.g., -p color:=red
2352
    // {
2353
    //   name: string // node name
2354
    //   parameters[] = {
2355
    //     name: string
2356
    //     type: uint
2357
    //     value: object
2358
    // }
2359
    const cliParamOverrideData = rclnodejs.getParameterOverrides(
892✔
2360
      this.context.handle
2361
    );
2362

2363
    // convert native CLI parameterOverrides to Map<nodeName,Array<ParameterOverride>>
2364
    const cliParamOverrides = new Map();
892✔
2365
    if (cliParamOverrideData) {
892✔
2366
      for (let nodeParamData of cliParamOverrideData) {
8✔
2367
        const nodeName = nodeParamData.name;
12✔
2368
        const nodeParamOverrides = [];
12✔
2369
        for (let paramData of nodeParamData.parameters) {
12✔
2370
          const paramOverride = new Parameter(
17✔
2371
            paramData.name,
2372
            paramData.type,
2373
            paramData.value
2374
          );
2375
          nodeParamOverrides.push(paramOverride);
17✔
2376
        }
2377
        cliParamOverrides.set(nodeName, nodeParamOverrides);
12✔
2378
      }
2379
    }
2380

2381
    // collect global CLI global parameters, name == /**
2382
    let paramOverrides = cliParamOverrides.get('/**'); // array of ParameterOverrides
892✔
2383
    if (paramOverrides) {
892✔
2384
      for (const parameter of paramOverrides) {
5✔
2385
        overrides.set(parameter.name, parameter);
6✔
2386
      }
2387
    }
2388

2389
    // merge CLI node parameterOverrides with global parameterOverrides, replace existing
2390
    paramOverrides = cliParamOverrides.get(this.name()); // array of ParameterOverrides
892✔
2391
    if (paramOverrides) {
892✔
2392
      for (const parameter of paramOverrides) {
5✔
2393
        overrides.set(parameter.name, parameter);
7✔
2394
      }
2395
    }
2396

2397
    return overrides;
892✔
2398
  }
2399

2400
  /**
2401
   * Invokes the callback with a raw message of the given type. After the callback completes
2402
   * the message will be destroyed.
2403
   * @param {function} Type - Message type to create.
2404
   * @param {function} callback - Callback to invoke. First parameter will be the raw message,
2405
   * and the second is a function to retrieve the deserialized message.
2406
   * @returns {undefined}
2407
   */
2408
  _runWithMessageType(Type, callback) {
2409
    let message = new Type();
863✔
2410

2411
    callback(message.toRawROS(), () => {
863✔
2412
      let result = new Type();
814✔
2413
      result.deserialize(message.refObject);
814✔
2414

2415
      return result;
814✔
2416
    });
2417

2418
    Type.destroyRawROS(message);
863✔
2419
  }
2420

2421
  _addActionClient(actionClient) {
2422
    this._actionClients.push(actionClient);
52✔
2423
    this.syncHandles();
52✔
2424
  }
2425

2426
  _addActionServer(actionServer) {
2427
    this._actionServers.push(actionServer);
52✔
2428
    this.syncHandles();
52✔
2429
  }
2430

2431
  _getValidatedTopic(topicName, noDemangle) {
2432
    if (noDemangle) {
6!
UNCOV
2433
      return topicName;
×
2434
    }
2435
    const fqTopicName = rclnodejs.expandTopicName(
6✔
2436
      topicName,
2437
      this.name(),
2438
      this.namespace()
2439
    );
2440
    validateFullTopicName(fqTopicName);
6✔
2441
    return rclnodejs.remapTopicName(this.handle, fqTopicName);
6✔
2442
  }
2443

2444
  _getValidatedServiceName(serviceName, noDemangle) {
2445
    if (typeof serviceName !== 'string') {
4!
UNCOV
2446
      throw new TypeValidationError('serviceName', serviceName, 'string', {
×
2447
        nodeName: this.name(),
2448
      });
2449
    }
2450

2451
    if (noDemangle) {
4!
UNCOV
2452
      return serviceName;
×
2453
    }
2454

2455
    const resolvedServiceName = this.resolveServiceName(serviceName);
4✔
2456
    rclnodejs.validateTopicName(resolvedServiceName);
4✔
2457
    return resolvedServiceName;
4✔
2458
  }
2459
}
2460

2461
/**
2462
 * Create an Options instance initialized with default values.
2463
 * @returns {Options} - The new initialized instance.
2464
 * @static
2465
 * @example
2466
 * {
2467
 *   enableTypedArray: true,
2468
 *   isRaw: false,
2469
 *   qos: QoS.profileDefault,
2470
 *   contentFilter: undefined,
2471
 *   serializationMode: 'default',
2472
 * }
2473
 */
2474
Node.getDefaultOptions = function () {
26✔
2475
  return {
8,208✔
2476
    enableTypedArray: true,
2477
    isRaw: false,
2478
    qos: QoS.profileDefault,
2479
    contentFilter: undefined,
2480
    serializationMode: 'default',
2481
  };
2482
};
2483

2484
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