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

RobotWebTools / rclnodejs / 27193208698

09 Jun 2026 08:17AM UTC coverage: 91.22% (+5.7%) from 85.523%
27193208698

push

github

web-flow
Phase 2: convert lib/, index.js and tests to native ES modules (#1530)

**Overview:** 189 files changed, +957 / −1162. Converts `lib/`, `index.js`, `bin/`, `rosocket/` and the full test suite to native ES modules; keeps build/codegen tooling as `.cjs`; updates CI to ROS 2 Lyrical (Ubuntu 26.04); and fixes a native-addon debug-build compile error.

### Core ESM conversion
- **`index.js`** — converted to ESM entrypoint (`import`/`export`), module wiring reworked.
- **`lib/**`** — all library modules converted from `require`/`module.exports` to `import`/`export` (node, client, service, publisher, subscription, action/*, clock*, parameter*, logging*, runtime/*, serialization, time*, timer, qos*, utils, validator, native_loader, etc.).
- **`bin/rclnodejs-web.js`**, **`rosocket/index.js`**, **`rosocket/cli.js`** — converted to ESM.

### ESM/CJS boundary fixes (from Copilot review)
- **`lib/native_loader.js`** — load the CommonJS `bindings` helper via `createRequire`'s `require('bindings')` instead of `import bindings from 'bindings'`, preserving CJS caller context for addon resolution.
- **`lib/type_description_service.js`** — corrected sibling import from `'../lib/parameter.js'` to `'./parameter.js'`.

### CommonJS files kept as `.cjs`
- **`rosidl_gen/*.cjs`** (deallocator, idl_generator, index, primitive_types, templates/message-template), **`rostsd_gen/index.cjs`**, **`scripts/ros_distro.cjs`**, **`scripts/run_test.cjs`** — build/codegen tooling stays CJS (loads ESM helpers via supported `require(esm)` / `.default`).
- **`third_party/ref-napi/`** — `lib/ref.js` and `package.json` tweaks for module resolution.

### Tooling / config
- **`package.json`** — `"type": "module"` and script adjustments.
- **`eslint.config.mjs`** — ESM lint rules.
- **`.c8rc.json`** added, **`.nycrc.yml`** removed — switch coverage from nyc to c8.

### CI
- **`.github/workflows/linux-x64-asan-test.yml`**, **`.github/workflows/linux-x64-build-and-test.yml`** — migrated from ROS 2 ... (continued)

2044 of 2402 branches covered (85.1%)

Branch coverage included in aggregate %.

369 of 370 new or added lines in 65 files covered. (99.73%)

942 existing lines in 47 files now uncovered.

16688 of 18133 relevant lines covered (92.03%)

228.85 hits per line

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

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

27✔
15
import rclnodejs from './native_loader.js';
27✔
16

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

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

27✔
60
/**
27✔
61
 * @class - Class representing a Node in ROS
27✔
62
 */
27✔
63

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

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

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

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

27✔
122
  _init(name, namespace, options, context, args, useGlobalArguments) {
27✔
123
    options = Node._normalizeOptions(options);
945✔
124

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

945✔
138
    this._context = context;
945✔
139
    this.context.onNodeCreated(this);
945✔
140

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

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

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

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

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

934✔
196
    // initialize _parameters from parameterOverrides
934✔
197
    if (options.automaticallyDeclareParametersFromOverrides) {
945✔
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
      }
10✔
204
    }
5✔
205

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

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

934✔
218
    if (options.enableLoggerService) {
945!
219
      this._loggerService = new LoggingService(this);
×
220
      this._loggerService.start();
×
UNCOV
221
    }
×
222

934✔
223
    if (
934✔
224
      DistroUtils.getDistroId() >= DistroUtils.getDistroId('jazzy') &&
934✔
225
      options.startTypeDescriptionService
934✔
226
    ) {
945✔
227
      this._typeDescriptionService = new TypeDescriptionService(this);
934✔
228
      this._typeDescriptionService.start();
934✔
229
    }
934✔
230
  }
945✔
231

27✔
232
  execute(handles) {
27✔
233
    let timersReady = this._timers.filter((timer) =>
4,924✔
234
      handles.includes(timer.handle)
4,084✔
235
    );
4,924✔
236
    let guardsReady = this._guards.filter((guard) =>
4,924✔
237
      handles.includes(guard.handle)
3✔
238
    );
4,924✔
239
    let subscriptionsReady = this._subscriptions.filter((subscription) =>
4,924✔
240
      handles.includes(subscription.handle)
445✔
241
    );
4,924✔
242
    let clientsReady = this._clients.filter((client) =>
4,924✔
243
      handles.includes(client.handle)
196✔
244
    );
4,924✔
245
    let servicesReady = this._services.filter((service) =>
4,924✔
246
      handles.includes(service.handle)
16,595✔
247
    );
4,924✔
248
    let actionClientsReady = this._actionClients.filter((actionClient) =>
4,924✔
249
      handles.includes(actionClient.handle)
211✔
250
    );
4,924✔
251
    let actionServersReady = this._actionServers.filter((actionServer) =>
4,924✔
252
      handles.includes(actionServer.handle)
205✔
253
    );
4,924✔
254
    let eventsReady = this._events.filter((event) =>
4,924✔
255
      handles.includes(event.handle)
4✔
256
    );
4,924✔
257

4,924✔
258
    timersReady.forEach((timer) => {
4,924✔
259
      if (timer.isReady()) {
4,074✔
260
        let timerInfo;
4,074✔
261
        if (typeof rclnodejs.callTimerWithInfo === 'function') {
4,074✔
262
          timerInfo = rclnodejs.callTimerWithInfo(timer.handle);
4,073✔
263
          timer.callback(timerInfo);
4,073✔
264
        } else {
4,074✔
265
          rclnodejs.callTimer(timer.handle);
1✔
266
          timer.callback();
1✔
267
        }
1✔
268
      }
4,074✔
269
    });
4,924✔
270

4,924✔
271
    eventsReady.forEach((event) => {
4,924✔
272
      event.takeData();
4✔
273
    });
4,924✔
274

4,924✔
275
    for (const subscription of subscriptionsReady) {
4,924✔
276
      if (subscription.isDestroyed()) continue;
420✔
277
      if (subscription.isRaw) {
420✔
278
        let rawMessage = rclnodejs.rclTakeRaw(subscription.handle);
1✔
279
        if (rawMessage) {
1✔
280
          subscription.processResponse(rawMessage);
1✔
281
        }
1✔
282
        continue;
1✔
283
      }
1✔
284

408✔
285
      this._runWithMessageType(
408✔
286
        subscription.typeClass,
408✔
287
        (message, deserialize) => {
408✔
288
          if (subscription.wantsMessageInfo) {
408✔
289
            let rawInfo = rclnodejs.rclTakeWithInfo(
4✔
290
              subscription.handle,
4✔
291
              message
4✔
292
            );
4✔
293
            if (rawInfo) {
4✔
294
              subscription.processResponse(
4✔
295
                deserialize(),
4✔
296
                new MessageInfo(rawInfo)
4✔
297
              );
4✔
298
            }
4✔
299
          } else {
408✔
300
            let success = rclnodejs.rclTake(subscription.handle, message);
404✔
301
            if (success) {
404✔
302
              subscription.processResponse(deserialize());
399✔
303
            }
399✔
304
          }
404✔
305
        }
408✔
306
      );
408✔
307
    }
408✔
308

4,924✔
309
    for (const guard of guardsReady) {
4,924✔
310
      if (guard.isDestroyed()) continue;
3!
311

3✔
312
      guard.callback();
3✔
313
    }
3✔
314

4,924✔
315
    for (const client of clientsReady) {
4,924✔
316
      if (client.isDestroyed()) continue;
101!
317
      this._runWithMessageType(
101✔
318
        client.typeClass.Response,
101✔
319
        (message, deserialize) => {
101✔
320
          let sequenceNumber = rclnodejs.rclTakeResponse(
101✔
321
            client.handle,
101✔
322
            message
101✔
323
          );
101✔
324
          if (sequenceNumber !== undefined) {
101✔
325
            client.processResponse(sequenceNumber, deserialize());
96✔
326
          }
96✔
327
        }
101✔
328
      );
101✔
329
    }
101✔
330

4,924✔
331
    for (const service of servicesReady) {
4,924✔
332
      if (service.isDestroyed()) continue;
139!
333
      this._runWithMessageType(
139✔
334
        service.typeClass.Request,
139✔
335
        (message, deserialize) => {
139✔
336
          let header = rclnodejs.rclTakeRequest(
139✔
337
            service.handle,
139✔
338
            this.handle,
139✔
339
            message
139✔
340
          );
139✔
341
          if (header) {
139✔
342
            service.processRequest(header, deserialize());
101✔
343
          }
101✔
344
        }
139✔
345
      );
139✔
346
    }
139✔
347

4,924✔
348
    for (const actionClient of actionClientsReady) {
4,924✔
349
      if (actionClient.isDestroyed()) continue;
126!
350

126✔
351
      const properties = actionClient.handle.properties;
126✔
352

126✔
353
      if (properties.isGoalResponseReady) {
126✔
354
        this._runWithMessageType(
57✔
355
          actionClient.typeClass.impl.SendGoalService.Response,
57✔
356
          (message, deserialize) => {
57✔
357
            let sequence = rclnodejs.actionTakeGoalResponse(
57✔
358
              actionClient.handle,
57✔
359
              message
57✔
360
            );
57✔
361
            if (sequence != undefined) {
57✔
362
              actionClient.processGoalResponse(sequence, deserialize());
50✔
363
            }
50✔
364
          }
57✔
365
        );
57✔
366
      }
57✔
367

126✔
368
      if (properties.isCancelResponseReady) {
126✔
369
        this._runWithMessageType(
5✔
370
          actionClient.typeClass.impl.CancelGoal.Response,
5✔
371
          (message, deserialize) => {
5✔
372
            let sequence = rclnodejs.actionTakeCancelResponse(
5✔
373
              actionClient.handle,
5✔
374
              message
5✔
375
            );
5✔
376
            if (sequence != undefined) {
5✔
377
              actionClient.processCancelResponse(sequence, deserialize());
5✔
378
            }
5✔
379
          }
5✔
380
        );
5✔
381
      }
5✔
382

126✔
383
      if (properties.isResultResponseReady) {
126✔
384
        this._runWithMessageType(
33✔
385
          actionClient.typeClass.impl.GetResultService.Response,
33✔
386
          (message, deserialize) => {
33✔
387
            let sequence = rclnodejs.actionTakeResultResponse(
33✔
388
              actionClient.handle,
33✔
389
              message
33✔
390
            );
33✔
391
            if (sequence != undefined) {
33✔
392
              actionClient.processResultResponse(sequence, deserialize());
33✔
393
            }
33✔
394
          }
33✔
395
        );
33✔
396
      }
33✔
397

126✔
398
      if (properties.isFeedbackReady) {
126✔
399
        this._runWithMessageType(
9✔
400
          actionClient.typeClass.impl.FeedbackMessage,
9✔
401
          (message, deserialize) => {
9✔
402
            let success = rclnodejs.actionTakeFeedback(
9✔
403
              actionClient.handle,
9✔
404
              message
9✔
405
            );
9✔
406
            if (success) {
9✔
407
              actionClient.processFeedbackMessage(deserialize());
9✔
408
            }
9✔
409
          }
9✔
410
        );
9✔
411
      }
9✔
412

126✔
413
      if (properties.isStatusReady) {
126✔
414
        this._runWithMessageType(
74✔
415
          actionClient.typeClass.impl.GoalStatusArray,
74✔
416
          (message, deserialize) => {
74✔
417
            let success = rclnodejs.actionTakeStatus(
74✔
418
              actionClient.handle,
74✔
419
              message
74✔
420
            );
74✔
421
            if (success) {
74✔
422
              actionClient.processStatusMessage(deserialize());
74✔
423
            }
74✔
424
          }
74✔
425
        );
74✔
426
      }
74✔
427
    }
126✔
428

4,924✔
429
    for (const actionServer of actionServersReady) {
4,924✔
430
      if (actionServer.isDestroyed()) continue;
97!
431

97✔
432
      const properties = actionServer.handle.properties;
97✔
433

97✔
434
      if (properties.isGoalRequestReady) {
97✔
435
        this._runWithMessageType(
55✔
436
          actionServer.typeClass.impl.SendGoalService.Request,
55✔
437
          (message, deserialize) => {
55✔
438
            const result = rclnodejs.actionTakeGoalRequest(
55✔
439
              actionServer.handle,
55✔
440
              message
55✔
441
            );
55✔
442
            if (result) {
55✔
443
              actionServer.processGoalRequest(result, deserialize());
50✔
444
            }
50✔
445
          }
55✔
446
        );
55✔
447
      }
55✔
448

97✔
449
      if (properties.isCancelRequestReady) {
97✔
450
        this._runWithMessageType(
5✔
451
          actionServer.typeClass.impl.CancelGoal.Request,
5✔
452
          (message, deserialize) => {
5✔
453
            const result = rclnodejs.actionTakeCancelRequest(
5✔
454
              actionServer.handle,
5✔
455
              message
5✔
456
            );
5✔
457
            if (result) {
5✔
458
              actionServer.processCancelRequest(result, deserialize());
5✔
459
            }
5✔
460
          }
5✔
461
        );
5✔
462
      }
5✔
463

97✔
464
      if (properties.isResultRequestReady) {
97✔
465
        this._runWithMessageType(
33✔
466
          actionServer.typeClass.impl.GetResultService.Request,
33✔
467
          (message, deserialize) => {
33✔
468
            const result = rclnodejs.actionTakeResultRequest(
33✔
469
              actionServer.handle,
33✔
470
              message
33✔
471
            );
33✔
472
            if (result) {
33✔
473
              actionServer.processResultRequest(result, deserialize());
33✔
474
            }
33✔
475
          }
33✔
476
        );
33✔
477
      }
33✔
478

97✔
479
      if (properties.isGoalExpired) {
97✔
480
        let numGoals = actionServer._goalHandles.size;
4✔
481
        if (numGoals > 0) {
4✔
482
          let GoalInfoArray = ActionInterfaces.GoalInfo.ArrayType;
4✔
483
          let message = new GoalInfoArray(numGoals);
4✔
484
          let count = rclnodejs.actionExpireGoals(
4✔
485
            actionServer.handle,
4✔
486
            numGoals,
4✔
487
            message._refArray.buffer
4✔
488
          );
4✔
489
          if (count > 0) {
4✔
490
            actionServer.processGoalExpired(message, count);
4✔
491
          }
4✔
492
          GoalInfoArray.freeArray(message);
4✔
493
        }
4✔
494
      }
4✔
495
    }
97✔
496

4,924✔
497
    // At this point it is safe to clear the cache of any
4,924✔
498
    // destroyed entity references
4,924✔
499
    Entity._gcHandles();
4,924✔
500
  }
4,924✔
501

27✔
502
  /**
27✔
503
   * Determine if this node is spinning.
27✔
504
   * @returns {boolean} - true when spinning; otherwise returns false.
27✔
505
   */
27✔
506
  get spinning() {
27✔
507
    return this._spinning;
4,690✔
508
  }
4,690✔
509

27✔
510
  /**
27✔
511
   * Trigger the event loop to continuously check for and route.
27✔
512
   * incoming events.
27✔
513
   * @param {Node} node - The node to be spun up.
27✔
514
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
27✔
515
   * @throws {Error} If the node is already spinning.
27✔
516
   * @return {undefined}
27✔
517
   */
27✔
518
  spin(timeout = 10) {
27✔
519
    if (this.spinning) {
721!
520
      throw new Error('The node is already spinning.');
×
UNCOV
521
    }
×
522
    this.start(this.context.handle, timeout);
721✔
523
    this._spinning = true;
721✔
524
  }
721✔
525

27✔
526
  /**
27✔
527
   * Use spin().
27✔
528
   * @deprecated, since 0.18.0
27✔
529
   */
27✔
530
  startSpinning(timeout) {
27✔
531
    this.spin(timeout);
×
UNCOV
532
  }
×
533

27✔
534
  /**
27✔
535
   * Terminate spinning - no further events will be received.
27✔
536
   * @returns {undefined}
27✔
537
   */
27✔
538
  stop() {
27✔
539
    super.stop();
721✔
540
    this._spinning = false;
721✔
541
  }
721✔
542

27✔
543
  /**
27✔
544
   * Terminate spinning - no further events will be received.
27✔
545
   * @returns {undefined}
27✔
546
   * @deprecated since 0.18.0, Use stop().
27✔
547
   */
27✔
548
  stopSpinning() {
27✔
549
    super.stop();
×
550
    this._spinning = false;
×
UNCOV
551
  }
×
552

27✔
553
  /**
27✔
554
   * Spin the node and trigger the event loop to check for one incoming event. Thereafter the node
27✔
555
   * will not received additional events until running additional calls to spin() or spinOnce().
27✔
556
   * @param {Node} node - The node to be spun.
27✔
557
   * @param {number} [timeout=10] - Timeout to wait in milliseconds. Block forever if negative. Don't wait if 0.
27✔
558
   * @throws {Error} If the node is already spinning.
27✔
559
   * @return {undefined}
27✔
560
   */
27✔
561
  spinOnce(timeout = 10) {
27✔
562
    if (this.spinning) {
3,009✔
563
      throw new Error('The node is already spinning.');
2✔
564
    }
2✔
565
    super.spinOnce(this.context.handle, timeout);
3,007✔
566
  }
3,009✔
567

27✔
568
  _removeEntityFromArray(entity, array) {
27✔
569
    let index = array.indexOf(entity);
444✔
570
    if (index > -1) {
444✔
571
      array.splice(index, 1);
442✔
572
    }
442✔
573
  }
444✔
574

27✔
575
  _destroyEntity(entity, array, syncHandles = true) {
27✔
576
    if (entity['isDestroyed'] && entity.isDestroyed()) return;
396✔
577

388✔
578
    this._removeEntityFromArray(entity, array);
388✔
579
    if (syncHandles) {
396✔
580
      this.syncHandles();
364✔
581
    }
364✔
582

388✔
583
    if (entity['_destroy']) {
396✔
584
      entity._destroy();
382✔
585
    } else {
396✔
586
      // guards and timers
6✔
587
      entity.handle.release();
6✔
588
    }
6✔
589
  }
396✔
590

27✔
591
  _validateOptions(options) {
27✔
592
    if (
8,655✔
593
      options !== undefined &&
8,655✔
594
      (options === null || typeof options !== 'object')
62✔
595
    ) {
8,655✔
596
      throw new TypeValidationError('options', options, 'object', {
20✔
597
        nodeName: this.name(),
20✔
598
      });
20✔
599
    }
20✔
600

8,635✔
601
    if (options === undefined) {
8,655✔
602
      return Node.getDefaultOptions();
8,593✔
603
    }
8,593✔
604

42✔
605
    if (options.enableTypedArray === undefined) {
8,438✔
606
      options = Object.assign(options, { enableTypedArray: true });
28✔
607
    }
28✔
608

42✔
609
    if (options.qos === undefined) {
8,438✔
610
      options = Object.assign(options, { qos: QoS.profileDefault });
20✔
611
    }
20✔
612

42✔
613
    if (options.isRaw === undefined) {
8,438✔
614
      options = Object.assign(options, { isRaw: false });
31✔
615
    }
31✔
616

42✔
617
    if (options.serializationMode === undefined) {
8,438✔
618
      options = Object.assign(options, { serializationMode: 'default' });
25✔
619
    } else if (!isValidSerializationMode(options.serializationMode)) {
8,438✔
620
      throw new ValidationError(
1✔
621
        `Invalid serializationMode: ${options.serializationMode}. Valid modes are: 'default', 'plain', 'json'`,
1✔
622
        {
1✔
623
          code: 'INVALID_SERIALIZATION_MODE',
1✔
624
          argumentName: 'serializationMode',
1✔
625
          providedValue: options.serializationMode,
1✔
626
          expectedType: "'default' | 'plain' | 'json'",
1✔
627
          nodeName: this.name(),
1✔
628
        }
1✔
629
      );
1✔
630
    }
1✔
631

41✔
632
    return options;
41✔
633
  }
8,655✔
634

27✔
635
  /**
27✔
636
   * Create a Timer.
27✔
637
   * @param {bigint} period - The number representing period in nanoseconds.
27✔
638
   * @param {function} callback - The callback to be called when the timer fires.
27✔
639
   *   On distros with native support, the callback receives a `TimerInfo` object
27✔
640
   *   describing the expected and actual call time.
27✔
641
   * @param {object|Clock} [optionsOrClock] - Timer options or the clock which the timer gets time from.
27✔
642
   *   Supported options: `{ autostart?: boolean }`.
27✔
643
   * @param {Clock} [clock] - The clock which the timer gets time from when options are provided.
27✔
644
   * @return {Timer} - An instance of Timer.
27✔
645
   */
27✔
646
  createTimer(period, callback, optionsOrClock = null, clock = null) {
27✔
647
    let options = {};
74✔
648

74✔
649
    if (optionsOrClock instanceof Clock.Clock) {
74!
650
      clock = optionsOrClock;
×
651
    } else if (optionsOrClock === null || optionsOrClock === undefined) {
74✔
652
      // Keep the 4th argument as the clock when the 3rd argument is omitted or explicitly null.
72✔
653
    } else {
74✔
654
      if (typeof optionsOrClock !== 'object' || Array.isArray(optionsOrClock)) {
2!
655
        throw new TypeValidationError(
×
UNCOV
656
          'options',
×
UNCOV
657
          optionsOrClock,
×
UNCOV
658
          'object or Clock',
×
UNCOV
659
          {
×
UNCOV
660
            nodeName: this.name(),
×
UNCOV
661
          }
×
UNCOV
662
        );
×
UNCOV
663
      }
×
664
      options = optionsOrClock;
2✔
665
    }
2✔
666

74✔
667
    if (
74✔
668
      arguments.length === 4 &&
74!
669
      clock !== null &&
74!
UNCOV
670
      !(clock instanceof Clock.Clock)
×
671
    ) {
74!
672
      throw new TypeValidationError('clock', clock, 'Clock', {
×
UNCOV
673
        nodeName: this.name(),
×
UNCOV
674
      });
×
UNCOV
675
    }
×
676

74✔
677
    if (typeof period !== 'bigint') {
74✔
678
      throw new TypeValidationError('period', period, 'bigint', {
1✔
679
        nodeName: this.name(),
1✔
680
      });
1✔
681
    }
1✔
682
    if (typeof callback !== 'function') {
74✔
683
      throw new TypeValidationError('callback', callback, 'function', {
1✔
684
        nodeName: this.name(),
1✔
685
      });
1✔
686
    }
1✔
687
    if (
72✔
688
      options.autostart !== undefined &&
74✔
689
      typeof options.autostart !== 'boolean'
2✔
690
    ) {
74✔
691
      throw new TypeValidationError(
1✔
692
        'options.autostart',
1✔
693
        options.autostart,
1✔
694
        'boolean',
1✔
695
        {
1✔
696
          nodeName: this.name(),
1✔
697
        }
1✔
698
      );
1✔
699
    }
1✔
700

71✔
701
    const timerClock = clock || this._clock;
74✔
702
    const autostart = options.autostart ?? true;
74✔
703
    let timerHandle = rclnodejs.createTimer(
74✔
704
      timerClock.handle,
74✔
705
      this.context.handle,
74✔
706
      period,
74✔
707
      autostart
74✔
708
    );
74✔
709
    let timer = new Timer(timerHandle, period, callback);
74✔
710
    debug('Finish creating timer, period = %d.', period);
74✔
711
    this._timers.push(timer);
74✔
712
    this.syncHandles();
74✔
713

74✔
714
    return timer;
74✔
715
  }
74✔
716

27✔
717
  /**
27✔
718
   * Create a Rate.
27✔
719
   *
27✔
720
   * @param {number} hz - The frequency of the rate timer; default is 1 hz.
27✔
721
   * @returns {Promise<Rate>} - Promise resolving to new instance of Rate.
27✔
722
   */
27✔
723
  async createRate(hz = 1) {
27✔
724
    if (typeof hz !== 'number') {
9!
725
      throw new TypeValidationError('hz', hz, 'number', {
×
UNCOV
726
        nodeName: this.name(),
×
UNCOV
727
      });
×
UNCOV
728
    }
×
729

9✔
730
    const MAX_RATE_HZ_IN_MILLISECOND = 1000.0;
9✔
731
    if (hz <= 0.0 || hz > MAX_RATE_HZ_IN_MILLISECOND) {
9✔
732
      throw new RangeValidationError(
2✔
733
        'hz',
2✔
734
        hz,
2✔
735
        `0.0 < hz <= ${MAX_RATE_HZ_IN_MILLISECOND}`,
2✔
736
        {
2✔
737
          nodeName: this.name(),
2✔
738
        }
2✔
739
      );
2✔
740
    }
2✔
741

7✔
742
    // lazy initialize rateTimerServer
7✔
743
    if (!this._rateTimerServer) {
9✔
744
      this._rateTimerServer = new Rates.RateTimerServer(this);
5✔
745
      await this._rateTimerServer.init();
5✔
746
    }
5✔
747

7✔
748
    const period = Math.round(1000 / hz);
7✔
749
    const timer = this._rateTimerServer.createTimer(BigInt(period) * 1000000n);
7✔
750
    const rate = new Rates.Rate(hz, timer);
7✔
751

7✔
752
    return rate;
7✔
753
  }
9✔
754

27✔
755
  /**
27✔
756
   * Create a Publisher.
27✔
757
   * @param {function|string|object} typeClass - The ROS message class,
27✔
758
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
27✔
759
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
27✔
760
   * @param {string} topic - The name of the topic.
27✔
761
   * @param {object} options - The options argument used to parameterize the publisher.
27✔
762
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
27✔
763
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the publisher, default: QoS.profileDefault.
27✔
764
   * @param {QoSOverridingOptions} [options.qosOverridingOptions] - If provided, declares read-only ROS parameters
27✔
765
   *  for the specified QoS policies (e.g. `qos_overrides./topic.publisher.depth`). These can be overridden at
27✔
766
   *  startup via `--ros-args -p` or `--params-file`. If qos is a profile string, it will be resolved to a
27✔
767
   *  mutable QoS object before overrides are applied.
27✔
768
   * @param {PublisherEventCallbacks} eventCallbacks - The event callbacks for the publisher.
27✔
769
   * @return {Publisher} - An instance of Publisher.
27✔
770
   */
27✔
771
  createPublisher(typeClass, topic, options, eventCallbacks) {
27✔
772
    return this._createPublisher(
1,334✔
773
      typeClass,
1,334✔
774
      topic,
1,334✔
775
      options,
1,334✔
776
      Publisher,
1,334✔
777
      eventCallbacks
1,334✔
778
    );
1,334✔
779
  }
1,334✔
780

27✔
781
  _createPublisher(typeClass, topic, options, publisherClass, eventCallbacks) {
27✔
782
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
1,337✔
783
      typeClass = loader.loadInterface(typeClass);
1,313✔
784
    }
1,313✔
785
    options = this._validateOptions(options);
1,330✔
786

1,330✔
787
    if (typeof typeClass !== 'function') {
1,337✔
788
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
789
        nodeName: this.name(),
8✔
790
        entityType: 'publisher',
8✔
791
      });
8✔
792
    }
8✔
793
    if (typeof topic !== 'string') {
1,337✔
794
      throw new TypeValidationError('topic', topic, 'string', {
12✔
795
        nodeName: this.name(),
12✔
796
        entityType: 'publisher',
12✔
797
      });
12✔
798
    }
12✔
799
    if (
1,310✔
800
      eventCallbacks &&
1,337✔
801
      !(eventCallbacks instanceof PublisherEventCallbacks)
2✔
802
    ) {
1,337!
803
      throw new TypeValidationError(
×
UNCOV
804
        'eventCallbacks',
×
UNCOV
805
        eventCallbacks,
×
UNCOV
806
        'PublisherEventCallbacks',
×
UNCOV
807
        {
×
UNCOV
808
          nodeName: this.name(),
×
UNCOV
809
          entityType: 'publisher',
×
UNCOV
810
          entityName: topic,
×
UNCOV
811
        }
×
UNCOV
812
      );
×
UNCOV
813
    }
×
814

1,310✔
815
    // Apply QoS overriding options if provided
1,310✔
816
    if (options.qosOverridingOptions) {
1,337✔
817
      const resolvedTopic = this.resolveTopicName(topic);
5✔
818
      if (typeof options.qos === 'string' || !(options.qos instanceof QoS)) {
5✔
819
        options.qos = _resolveQoS(options.qos);
2✔
820
      }
2✔
821
      declareQosParameters(
5✔
822
        'publisher',
5✔
823
        this,
5✔
824
        resolvedTopic,
5✔
825
        options.qos,
5✔
826
        options.qosOverridingOptions
5✔
827
      );
5✔
828
    }
5✔
829

1,309✔
830
    let publisher = publisherClass.createPublisher(
1,309✔
831
      this,
1,309✔
832
      typeClass,
1,309✔
833
      topic,
1,309✔
834
      options,
1,309✔
835
      eventCallbacks
1,309✔
836
    );
1,309✔
837
    debug('Finish creating publisher, topic = %s.', topic);
1,309✔
838
    this._publishers.push(publisher);
1,309✔
839
    return publisher;
1,309✔
840
  }
1,337✔
841

27✔
842
  /**
27✔
843
   * This callback is called when a message is published
27✔
844
   * @callback SubscriptionCallback
27✔
845
   * @param {Object} message - The message published
27✔
846
   * @see [Node.createSubscription]{@link Node#createSubscription}
27✔
847
   * @see [Node.createPublisher]{@link Node#createPublisher}
27✔
848
   * @see {@link Publisher}
27✔
849
   * @see {@link Subscription}
27✔
850
   */
27✔
851

27✔
852
  /**
27✔
853
   * Create a Subscription with optional content-filtering.
27✔
854
   * @param {function|string|object} typeClass - The ROS message class,
27✔
855
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
27✔
856
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
27✔
857
   * @param {string} topic - The name of the topic.
27✔
858
   * @param {object} options - The options argument used to parameterize the subscription.
27✔
859
   * @param {boolean} options.enableTypedArray - The topic will use TypedArray if necessary, default: true.
27✔
860
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the subscription, default: QoS.profileDefault.
27✔
861
   * @param {boolean} options.isRaw - The topic is serialized when true, default: false.
27✔
862
   * @param {string} [options.serializationMode='default'] - Controls message serialization format:
27✔
863
   *  'default': Use native rclnodejs behavior (respects enableTypedArray setting),
27✔
864
   *  'plain': Convert TypedArrays to regular arrays,
27✔
865
   *  'json': Fully JSON-safe (handles TypedArrays, BigInt, etc.).
27✔
866
   * @param {object} [options.contentFilter=undefined] - The content-filter, default: undefined.
27✔
867
   *  Confirm that your RMW supports content-filtered topics before use. 
27✔
868
   * @param {string} options.contentFilter.expression - Specifies the criteria to select the data samples of
27✔
869
   *  interest. It is similar to the WHERE part of an SQL clause.
27✔
870
   * @param {string[]} [options.contentFilter.parameters=undefined] - Array of strings that give values to
27✔
871
   *  the ‘parameters’ (i.e., "%n" tokens) in the filter_expression. The number of supplied parameters must
27✔
872
   *  fit with the requested values in the filter_expression (i.e., the number of %n tokens). default: undefined.
27✔
873
   * @param {QoSOverridingOptions} [options.qosOverridingOptions] - If provided, declares read-only ROS parameters
27✔
874
   *  for the specified QoS policies (e.g. `qos_overrides./topic.subscription.depth`). These can be overridden at
27✔
875
   *  startup via `--ros-args -p` or `--params-file`. If qos is a profile string, it will be resolved to a
27✔
876
   *  mutable QoS object before overrides are applied.
27✔
877
   * @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.
27✔
878
   * @param {SubscriptionEventCallbacks} eventCallbacks - The event callbacks for the subscription.
27✔
879
   * @return {Subscription} - An instance of Subscription.
27✔
880
   * @throws {ERROR} - May throw an RMW error if content-filter is malformed. 
27✔
881
   * @see {@link SubscriptionCallback}
27✔
882
   * @see {@link https://www.omg.org/spec/DDS/1.4/PDF|Content-filter details at DDS 1.4 specification, Annex B}
27✔
883
   */
27✔
884
  createSubscription(typeClass, topic, options, callback, eventCallbacks) {
27✔
885
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
487✔
886
      typeClass = loader.loadInterface(typeClass);
478✔
887
    }
478✔
888

480✔
889
    if (typeof options === 'function') {
487✔
890
      callback = options;
363✔
891
      options = undefined;
363✔
892
    }
363✔
893
    options = this._validateOptions(options);
480✔
894

480✔
895
    if (typeof typeClass !== 'function') {
487✔
896
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
897
        nodeName: this.name(),
4✔
898
        entityType: 'subscription',
4✔
899
      });
4✔
900
    }
4✔
901
    if (typeof topic !== 'string') {
487✔
902
      throw new TypeValidationError('topic', topic, 'string', {
6✔
903
        nodeName: this.name(),
6✔
904
        entityType: 'subscription',
6✔
905
      });
6✔
906
    }
6✔
907
    if (typeof callback !== 'function') {
487!
908
      throw new TypeValidationError('callback', callback, 'function', {
×
UNCOV
909
        nodeName: this.name(),
×
UNCOV
910
        entityType: 'subscription',
×
UNCOV
911
        entityName: topic,
×
UNCOV
912
      });
×
UNCOV
913
    }
×
914
    if (
460✔
915
      eventCallbacks &&
487✔
916
      !(eventCallbacks instanceof SubscriptionEventCallbacks)
4✔
917
    ) {
487!
918
      throw new TypeValidationError(
×
UNCOV
919
        'eventCallbacks',
×
UNCOV
920
        eventCallbacks,
×
UNCOV
921
        'SubscriptionEventCallbacks',
×
UNCOV
922
        {
×
UNCOV
923
          nodeName: this.name(),
×
UNCOV
924
          entityType: 'subscription',
×
UNCOV
925
          entityName: topic,
×
UNCOV
926
        }
×
UNCOV
927
      );
×
UNCOV
928
    }
×
929

460✔
930
    // Apply QoS overriding options if provided
460✔
931
    if (options.qosOverridingOptions) {
487✔
932
      const resolvedTopic = this.resolveTopicName(topic);
2✔
933
      if (typeof options.qos === 'string' || !(options.qos instanceof QoS)) {
2!
934
        options.qos = _resolveQoS(options.qos);
×
UNCOV
935
      }
×
936
      declareQosParameters(
2✔
937
        'subscription',
2✔
938
        this,
2✔
939
        resolvedTopic,
2✔
940
        options.qos,
2✔
941
        options.qosOverridingOptions
2✔
942
      );
2✔
943
    }
2✔
944

460✔
945
    let subscription = Subscription.createSubscription(
460✔
946
      this,
460✔
947
      typeClass,
460✔
948
      topic,
460✔
949
      options,
460✔
950
      callback,
460✔
951
      eventCallbacks
460✔
952
    );
460✔
953
    debug('Finish creating subscription, topic = %s.', topic);
460✔
954
    this._subscriptions.push(subscription);
460✔
955
    this.syncHandles();
460✔
956

460✔
957
    return subscription;
460✔
958
  }
487✔
959

27✔
960
  /**
27✔
961
   * Create a Subscription that returns an RxJS Observable.
27✔
962
   * This allows using reactive programming patterns with ROS 2 messages.
27✔
963
   *
27✔
964
   * @param {function|string|object} typeClass - The ROS message class,
27✔
965
   *      OR a string representing the message class, e.g. 'std_msgs/msg/String',
27✔
966
   *      OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
27✔
967
   * @param {string} topic - The name of the topic.
27✔
968
   * @param {object} [options] - The options argument used to parameterize the subscription.
27✔
969
   * @param {boolean} [options.enableTypedArray=true] - The topic will use TypedArray if necessary.
27✔
970
   * @param {QoS} [options.qos=QoS.profileDefault] - ROS Middleware "quality of service" settings.
27✔
971
   * @param {boolean} [options.isRaw=false] - The topic is serialized when true.
27✔
972
   * @param {string} [options.serializationMode='default'] - Controls message serialization format.
27✔
973
   * @param {object} [options.contentFilter] - The content-filter (if supported by RMW).
27✔
974
   * @param {SubscriptionEventCallbacks} [eventCallbacks] - The event callbacks for the subscription.
27✔
975
   * @return {ObservableSubscription} - An ObservableSubscription with an RxJS Observable.
27✔
976
   */
27✔
977
  createObservableSubscription(typeClass, topic, options, eventCallbacks) {
27✔
978
    let observableSubscription = null;
7✔
979

7✔
980
    const subscription = this.createSubscription(
7✔
981
      typeClass,
7✔
982
      topic,
7✔
983
      options,
7✔
984
      (message) => {
7✔
985
        if (observableSubscription) {
8✔
986
          observableSubscription._emit(message);
8✔
987
        }
8✔
988
      },
7✔
989
      eventCallbacks
7✔
990
    );
7✔
991

7✔
992
    observableSubscription = new ObservableSubscription(subscription);
7✔
993
    return observableSubscription;
7✔
994
  }
7✔
995

27✔
996
  /**
27✔
997
   * Create a Client.
27✔
998
   * @param {function|string|object} typeClass - The ROS message class,
27✔
999
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
27✔
1000
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
27✔
1001
   * @param {string} serviceName - The service name to request.
27✔
1002
   * @param {object} options - The options argument used to parameterize the client.
27✔
1003
   * @param {boolean} options.enableTypedArray - The response will use TypedArray if necessary, default: true.
27✔
1004
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the client, default: QoS.profileDefault.
27✔
1005
   * @return {Client} - An instance of Client.
27✔
1006
   */
27✔
1007
  createClient(typeClass, serviceName, options) {
27✔
1008
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
208✔
1009
      typeClass = loader.loadInterface(typeClass);
197✔
1010
    }
197✔
1011
    options = this._validateOptions(options);
201✔
1012

201✔
1013
    if (typeof typeClass !== 'function') {
208✔
1014
      throw new TypeValidationError('typeClass', typeClass, 'function', {
8✔
1015
        nodeName: this.name(),
8✔
1016
        entityType: 'client',
8✔
1017
      });
8✔
1018
    }
8✔
1019
    if (typeof serviceName !== 'string') {
208✔
1020
      throw new TypeValidationError('serviceName', serviceName, 'string', {
12✔
1021
        nodeName: this.name(),
12✔
1022
        entityType: 'client',
12✔
1023
      });
12✔
1024
    }
12✔
1025

181✔
1026
    let client = Client.createClient(
181✔
1027
      this.handle,
181✔
1028
      serviceName,
181✔
1029
      typeClass,
181✔
1030
      options
181✔
1031
    );
181✔
1032
    debug('Finish creating client, service = %s.', serviceName);
181✔
1033
    this._clients.push(client);
181✔
1034
    this.syncHandles();
181✔
1035

181✔
1036
    return client;
181✔
1037
  }
208✔
1038

27✔
1039
  /**
27✔
1040
   * This callback is called when a request is sent to service
27✔
1041
   * @callback RequestCallback
27✔
1042
   * @param {Object} request - The request sent to the service
27✔
1043
   * @param {Response} response - The response to client.
27✔
1044
        Use [response.send()]{@link Response#send} to send response object to client
27✔
1045
   * @return {undefined}
27✔
1046
   * @see [Node.createService]{@link Node#createService}
27✔
1047
   * @see [Client.sendRequest]{@link Client#sendRequest}
27✔
1048
   * @see {@link Client}
27✔
1049
   * @see {@link Service}
27✔
1050
   * @see {@link Response#send}
27✔
1051
   */
27✔
1052

27✔
1053
  /**
27✔
1054
   * Create a Service.
27✔
1055
   * @param {function|string|object} typeClass - The ROS message class,
27✔
1056
        OR a string representing the message class, e.g. 'std_msgs/msg/String',
27✔
1057
        OR an object representing the message class, e.g. {package: 'std_msgs', type: 'msg', name: 'String'}
27✔
1058
   * @param {string} serviceName - The service name to offer.
27✔
1059
   * @param {object} options - The options argument used to parameterize the service.
27✔
1060
   * @param {boolean} options.enableTypedArray - The request will use TypedArray if necessary, default: true.
27✔
1061
   * @param {QoS} options.qos - ROS Middleware "quality of service" settings for the service, default: QoS.profileDefault.
27✔
1062
   * @param {RequestCallback} callback - The callback to be called when receiving request.
27✔
1063
   * @return {Service} - An instance of Service.
27✔
1064
   * @see {@link RequestCallback}
27✔
1065
   */
27✔
1066
  createService(typeClass, serviceName, options, callback) {
27✔
1067
    if (typeof typeClass === 'string' || typeof typeClass === 'object') {
5,641✔
1068
      typeClass = loader.loadInterface(typeClass);
5,630✔
1069
    }
5,630✔
1070

5,634✔
1071
    if (typeof options === 'function') {
5,641✔
1072
      callback = options;
5,611✔
1073
      options = undefined;
5,611✔
1074
    }
5,611✔
1075
    options = this._validateOptions(options);
5,634✔
1076

5,634✔
1077
    if (typeof typeClass !== 'function') {
5,641✔
1078
      throw new TypeValidationError('typeClass', typeClass, 'function', {
4✔
1079
        nodeName: this.name(),
4✔
1080
        entityType: 'service',
4✔
1081
      });
4✔
1082
    }
4✔
1083
    if (typeof serviceName !== 'string') {
5,641✔
1084
      throw new TypeValidationError('serviceName', serviceName, 'string', {
6✔
1085
        nodeName: this.name(),
6✔
1086
        entityType: 'service',
6✔
1087
      });
6✔
1088
    }
6✔
1089
    if (typeof callback !== 'function') {
5,641!
1090
      throw new TypeValidationError('callback', callback, 'function', {
×
UNCOV
1091
        nodeName: this.name(),
×
UNCOV
1092
        entityType: 'service',
×
UNCOV
1093
        entityName: serviceName,
×
UNCOV
1094
      });
×
UNCOV
1095
    }
×
1096

5,614✔
1097
    let service = Service.createService(
5,614✔
1098
      this.handle,
5,614✔
1099
      serviceName,
5,614✔
1100
      typeClass,
5,614✔
1101
      options,
5,614✔
1102
      callback
5,614✔
1103
    );
5,614✔
1104
    debug('Finish creating service, service = %s.', serviceName);
5,614✔
1105
    this._services.push(service);
5,614✔
1106
    this.syncHandles();
5,614✔
1107

5,614✔
1108
    return service;
5,614✔
1109
  }
5,641✔
1110

27✔
1111
  /**
27✔
1112
   * Create a ParameterClient for accessing parameters on a remote node.
27✔
1113
   * @param {string} remoteNodeName - The name of the remote node whose parameters to access.
27✔
1114
   * @param {object} [options] - Options for parameter client.
27✔
1115
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
27✔
1116
   * @return {ParameterClient} - An instance of ParameterClient.
27✔
1117
   */
27✔
1118
  createParameterClient(remoteNodeName, options = {}) {
27✔
1119
    if (typeof remoteNodeName !== 'string' || remoteNodeName.trim() === '') {
103!
1120
      throw new TypeError('Remote node name must be a non-empty string');
×
UNCOV
1121
    }
×
1122

103✔
1123
    const parameterClient = new ParameterClient(this, remoteNodeName, options);
103✔
1124
    debug(
103✔
1125
      'Finish creating parameter client for remote node = %s.',
103✔
1126
      remoteNodeName
103✔
1127
    );
103✔
1128
    this._parameterClients.push(parameterClient);
103✔
1129

103✔
1130
    return parameterClient;
103✔
1131
  }
103✔
1132

27✔
1133
  /**
27✔
1134
   * Create a ParameterWatcher for watching parameter changes on a remote node.
27✔
1135
   * @param {string} remoteNodeName - The name of the remote node whose parameters to watch.
27✔
1136
   * @param {string[]} parameterNames - Array of parameter names to watch.
27✔
1137
   * @param {object} [options] - Options for parameter watcher.
27✔
1138
   * @param {number} [options.timeout=5000] - Default timeout in milliseconds for service calls.
27✔
1139
   * @return {ParameterWatcher} - An instance of ParameterWatcher.
27✔
1140
   */
27✔
1141
  createParameterWatcher(remoteNodeName, parameterNames, options = {}) {
27✔
1142
    const watcher = new ParameterWatcher(
57✔
1143
      this,
57✔
1144
      remoteNodeName,
57✔
1145
      parameterNames,
57✔
1146
      options
57✔
1147
    );
57✔
1148
    debug(
57✔
1149
      'Finish creating parameter watcher for remote node = %s.',
57✔
1150
      remoteNodeName
57✔
1151
    );
57✔
1152
    this._parameterWatchers.push(watcher);
57✔
1153

57✔
1154
    return watcher;
57✔
1155
  }
57✔
1156

27✔
1157
  /**
27✔
1158
   * Create a guard condition.
27✔
1159
   * @param {Function} callback - The callback to be called when the guard condition is triggered.
27✔
1160
   * @return {GuardCondition} - An instance of GuardCondition.
27✔
1161
   */
27✔
1162
  createGuardCondition(callback) {
27✔
1163
    if (typeof callback !== 'function') {
3!
1164
      throw new TypeValidationError('callback', callback, 'function', {
×
UNCOV
1165
        nodeName: this.name(),
×
UNCOV
1166
        entityType: 'guard_condition',
×
UNCOV
1167
      });
×
UNCOV
1168
    }
×
1169

3✔
1170
    let guard = GuardCondition.createGuardCondition(callback, this.context);
3✔
1171
    debug('Finish creating guard condition');
3✔
1172
    this._guards.push(guard);
3✔
1173
    this.syncHandles();
3✔
1174

3✔
1175
    return guard;
3✔
1176
  }
3✔
1177

27✔
1178
  /**
27✔
1179
   * Destroy all resource allocated by this node, including
27✔
1180
   * <code>Timer</code>s/<code>Publisher</code>s/<code>Subscription</code>s
27✔
1181
   * /<code>Client</code>s/<code>Service</code>s
27✔
1182
   * @return {undefined}
27✔
1183
   */
27✔
1184
  destroy() {
27✔
1185
    if (this.spinning) {
958✔
1186
      this.stop();
629✔
1187
    }
629✔
1188

958✔
1189
    // Action servers/clients require manual destruction due to circular reference with goal handles.
958✔
1190
    this._actionClients.forEach((actionClient) => actionClient.destroy());
958✔
1191
    this._actionServers.forEach((actionServer) => actionServer.destroy());
958✔
1192

958✔
1193
    this._parameterClients.forEach((paramClient) => paramClient.destroy());
958✔
1194
    this._parameterWatchers.forEach((watcher) => watcher.destroy());
958✔
1195
    this._parameterEventHandlers.forEach((handler) => handler.destroy());
958✔
1196

958✔
1197
    this.context.onNodeDestroyed(this);
958✔
1198

958✔
1199
    if (this._enableRosout) {
958✔
1200
      rclnodejs.finiRosoutPublisherForNode(this.handle);
933✔
1201
      this._enableRosout = false;
933✔
1202
    }
933✔
1203

958✔
1204
    this.handle.release();
958✔
1205
    this._clock = null;
958✔
1206
    this._timers = [];
958✔
1207
    this._publishers = [];
958✔
1208
    this._subscriptions = [];
958✔
1209
    this._clients = [];
958✔
1210
    this._services = [];
958✔
1211
    this._guards = [];
958✔
1212
    this._actionClients = [];
958✔
1213
    this._actionServers = [];
958✔
1214
    this._parameterClients = [];
958✔
1215
    this._parameterWatchers = [];
958✔
1216
    this._parameterEventHandlers = [];
958✔
1217

958✔
1218
    if (this._rateTimerServer) {
958✔
1219
      this._rateTimerServer.shutdown();
5✔
1220
      this._rateTimerServer = null;
5✔
1221
    }
5✔
1222
  }
958✔
1223

27✔
1224
  /**
27✔
1225
   * Destroy a Publisher.
27✔
1226
   * @param {Publisher} publisher - The Publisher to be destroyed.
27✔
1227
   * @return {undefined}
27✔
1228
   */
27✔
1229
  destroyPublisher(publisher) {
27✔
1230
    if (!(publisher instanceof Publisher)) {
28✔
1231
      throw new TypeValidationError(
2✔
1232
        'publisher',
2✔
1233
        publisher,
2✔
1234
        'Publisher instance',
2✔
1235
        {
2✔
1236
          nodeName: this.name(),
2✔
1237
        }
2✔
1238
      );
2✔
1239
    }
2✔
1240
    if (publisher.events) {
28!
1241
      publisher.events.forEach((event) => {
×
1242
        this._destroyEntity(event, this._events);
×
UNCOV
1243
      });
×
1244
      publisher.events = [];
×
UNCOV
1245
    }
×
1246
    this._destroyEntity(publisher, this._publishers, false);
26✔
1247
  }
28✔
1248

27✔
1249
  /**
27✔
1250
   * Destroy a Subscription.
27✔
1251
   * @param {Subscription} subscription - The Subscription to be destroyed.
27✔
1252
   * @return {undefined}
27✔
1253
   */
27✔
1254
  destroySubscription(subscription) {
27✔
1255
    if (!(subscription instanceof Subscription)) {
125✔
1256
      throw new TypeValidationError(
2✔
1257
        'subscription',
2✔
1258
        subscription,
2✔
1259
        'Subscription instance',
2✔
1260
        {
2✔
1261
          nodeName: this.name(),
2✔
1262
        }
2✔
1263
      );
2✔
1264
    }
2✔
1265
    if (subscription.events) {
125✔
1266
      subscription.events.forEach((event) => {
1✔
1267
        this._destroyEntity(event, this._events);
1✔
1268
      });
1✔
1269
      subscription.events = [];
1✔
1270
    }
1✔
1271

123✔
1272
    this._destroyEntity(subscription, this._subscriptions);
123✔
1273
  }
125✔
1274

27✔
1275
  /**
27✔
1276
   * Destroy a Client.
27✔
1277
   * @param {Client} client - The Client to be destroyed.
27✔
1278
   * @return {undefined}
27✔
1279
   */
27✔
1280
  destroyClient(client) {
27✔
1281
    if (!(client instanceof Client)) {
127✔
1282
      throw new TypeValidationError('client', client, 'Client instance', {
2✔
1283
        nodeName: this.name(),
2✔
1284
      });
2✔
1285
    }
2✔
1286
    this._destroyEntity(client, this._clients);
125✔
1287
  }
127✔
1288

27✔
1289
  /**
27✔
1290
   * Destroy a Service.
27✔
1291
   * @param {Service} service - The Service to be destroyed.
27✔
1292
   * @return {undefined}
27✔
1293
   */
27✔
1294
  destroyService(service) {
27✔
1295
    if (!(service instanceof Service)) {
13✔
1296
      throw new TypeValidationError('service', service, 'Service instance', {
2✔
1297
        nodeName: this.name(),
2✔
1298
      });
2✔
1299
    }
2✔
1300
    this._destroyEntity(service, this._services);
11✔
1301
  }
13✔
1302

27✔
1303
  /**
27✔
1304
   * Destroy a ParameterClient.
27✔
1305
   * @param {ParameterClient} parameterClient - The ParameterClient to be destroyed.
27✔
1306
   * @return {undefined}
27✔
1307
   */
27✔
1308
  destroyParameterClient(parameterClient) {
27✔
1309
    if (!(parameterClient instanceof ParameterClient)) {
54!
1310
      throw new TypeError('Invalid argument');
×
UNCOV
1311
    }
×
1312
    this._removeEntityFromArray(parameterClient, this._parameterClients);
54✔
1313
    parameterClient.destroy();
54✔
1314
  }
54✔
1315

27✔
1316
  /**
27✔
1317
   * Destroy a ParameterWatcher.
27✔
1318
   * @param {ParameterWatcher} watcher - The ParameterWatcher to be destroyed.
27✔
1319
   * @return {undefined}
27✔
1320
   */
27✔
1321
  destroyParameterWatcher(watcher) {
27✔
1322
    if (!(watcher instanceof ParameterWatcher)) {
1!
1323
      throw new TypeError('Invalid argument');
×
UNCOV
1324
    }
×
1325
    this._removeEntityFromArray(watcher, this._parameterWatchers);
1✔
1326
    watcher.destroy();
1✔
1327
  }
1✔
1328

27✔
1329
  /**
27✔
1330
   * Create a ParameterEventHandler that monitors parameter changes on any node.
27✔
1331
   *
27✔
1332
   * Unlike {@link ParameterWatcher} which watches specific parameters on a single
27✔
1333
   * remote node, ParameterEventHandler can register callbacks for parameters on
27✔
1334
   * any node in the ROS 2 graph by subscribing to /parameter_events.
27✔
1335
   *
27✔
1336
   * @param {object} [options] - Options for the handler
27✔
1337
   * @param {object} [options.qos] - QoS profile for the parameter_events subscription
27✔
1338
   * @return {ParameterEventHandler} - An instance of ParameterEventHandler
27✔
1339
   * @see {@link ParameterEventHandler}
27✔
1340
   */
27✔
1341
  createParameterEventHandler(options = {}) {
27✔
1342
    const handler = new ParameterEventHandler(this, options);
18✔
1343
    debug('Created ParameterEventHandler on node=%s', this.name());
18✔
1344
    this._parameterEventHandlers.push(handler);
18✔
1345
    return handler;
18✔
1346
  }
18✔
1347

27✔
1348
  /**
27✔
1349
   * Destroy a ParameterEventHandler.
27✔
1350
   * @param {ParameterEventHandler} handler - The handler to be destroyed.
27✔
1351
   * @return {undefined}
27✔
1352
   */
27✔
1353
  destroyParameterEventHandler(handler) {
27✔
1354
    if (!(handler instanceof ParameterEventHandler)) {
1!
1355
      throw new TypeError('Invalid argument');
×
UNCOV
1356
    }
×
1357
    this._removeEntityFromArray(handler, this._parameterEventHandlers);
1✔
1358
    handler.destroy();
1✔
1359
  }
1✔
1360

27✔
1361
  /**
27✔
1362
   * Destroy a Timer.
27✔
1363
   * @param {Timer} timer - The Timer to be destroyed.
27✔
1364
   * @return {undefined}
27✔
1365
   */
27✔
1366
  destroyTimer(timer) {
27✔
1367
    if (!(timer instanceof Timer)) {
8✔
1368
      throw new TypeValidationError('timer', timer, 'Timer instance', {
2✔
1369
        nodeName: this.name(),
2✔
1370
      });
2✔
1371
    }
2✔
1372
    this._destroyEntity(timer, this._timers);
6✔
1373
  }
8✔
1374

27✔
1375
  /**
27✔
1376
   * Destroy a guard condition.
27✔
1377
   * @param {GuardCondition} guard - The guard condition to be destroyed.
27✔
1378
   * @return {undefined}
27✔
1379
   */
27✔
1380
  destroyGuardCondition(guard) {
27✔
1381
    if (!(guard instanceof GuardCondition)) {
3!
1382
      throw new TypeValidationError('guard', guard, 'GuardCondition instance', {
×
UNCOV
1383
        nodeName: this.name(),
×
UNCOV
1384
      });
×
UNCOV
1385
    }
×
1386
    this._destroyEntity(guard, this._guards);
3✔
1387
  }
3✔
1388

27✔
1389
  /**
27✔
1390
   * Get the name of the node.
27✔
1391
   * @return {string}
27✔
1392
   */
27✔
1393
  name() {
27✔
1394
    return rclnodejs.getNodeName(this.handle);
5,578✔
1395
  }
5,578✔
1396

27✔
1397
  /**
27✔
1398
   * Get the namespace of the node.
27✔
1399
   * @return {string}
27✔
1400
   */
27✔
1401
  namespace() {
27✔
1402
    return rclnodejs.getNamespace(this.handle);
5,180✔
1403
  }
5,180✔
1404

27✔
1405
  /**
27✔
1406
   * Get the context in which this node was created.
27✔
1407
   * @return {Context}
27✔
1408
   */
27✔
1409
  get context() {
27✔
1410
    return this._context;
6,631✔
1411
  }
6,631✔
1412

27✔
1413
  /**
27✔
1414
   * Get the nodes logger.
27✔
1415
   * @returns {Logger} - The logger for the node.
27✔
1416
   */
27✔
1417
  getLogger() {
27✔
1418
    return this._logger;
248✔
1419
  }
248✔
1420

27✔
1421
  /**
27✔
1422
   * Get the clock used by the node.
27✔
1423
   * @returns {Clock} - The nodes clock.
27✔
1424
   */
27✔
1425
  getClock() {
27✔
1426
    return this._clock;
119✔
1427
  }
119✔
1428

27✔
1429
  /**
27✔
1430
   * Get the current time using the node's clock.
27✔
1431
   * @returns {Timer} - The current time.
27✔
1432
   */
27✔
1433
  now() {
27✔
1434
    return this.getClock().now();
2✔
1435
  }
2✔
1436

27✔
1437
  /**
27✔
1438
   * Get the list of published topics discovered by the provided node for the remote node name.
27✔
1439
   * @param {string} nodeName - The name of the node.
27✔
1440
   * @param {string} namespace - The name of the namespace.
27✔
1441
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
27✔
1442
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1443
   */
27✔
1444
  getPublisherNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
27✔
1445
    return rclnodejs.getPublisherNamesAndTypesByNode(
2✔
1446
      this.handle,
2✔
1447
      nodeName,
2✔
1448
      namespace,
2✔
1449
      noDemangle
2✔
1450
    );
2✔
1451
  }
2✔
1452

27✔
1453
  /**
27✔
1454
   * Get the list of published topics discovered by the provided node for the remote node name.
27✔
1455
   * @param {string} nodeName - The name of the node.
27✔
1456
   * @param {string} namespace - The name of the namespace.
27✔
1457
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
27✔
1458
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1459
   */
27✔
1460
  getSubscriptionNamesAndTypesByNode(nodeName, namespace, noDemangle = false) {
27✔
1461
    return rclnodejs.getSubscriptionNamesAndTypesByNode(
×
UNCOV
1462
      this.handle,
×
UNCOV
1463
      nodeName,
×
UNCOV
1464
      namespace,
×
UNCOV
1465
      noDemangle
×
UNCOV
1466
    );
×
UNCOV
1467
  }
×
1468

27✔
1469
  /**
27✔
1470
   * Get service names and types for which a remote node has servers.
27✔
1471
   * @param {string} nodeName - The name of the node.
27✔
1472
   * @param {string} namespace - The name of the namespace.
27✔
1473
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1474
   */
27✔
1475
  getServiceNamesAndTypesByNode(nodeName, namespace) {
27✔
1476
    return rclnodejs.getServiceNamesAndTypesByNode(
×
UNCOV
1477
      this.handle,
×
UNCOV
1478
      nodeName,
×
UNCOV
1479
      namespace
×
UNCOV
1480
    );
×
UNCOV
1481
  }
×
1482

27✔
1483
  /**
27✔
1484
   * Get service names and types for which a remote node has clients.
27✔
1485
   * @param {string} nodeName - The name of the node.
27✔
1486
   * @param {string} namespace - The name of the namespace.
27✔
1487
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1488
   */
27✔
1489
  getClientNamesAndTypesByNode(nodeName, namespace) {
27✔
1490
    return rclnodejs.getClientNamesAndTypesByNode(
×
UNCOV
1491
      this.handle,
×
UNCOV
1492
      nodeName,
×
UNCOV
1493
      namespace
×
UNCOV
1494
    );
×
UNCOV
1495
  }
×
1496

27✔
1497
  /**
27✔
1498
   * Get the list of topics discovered by the provided node.
27✔
1499
   * @param {boolean} noDemangle - If true topic names and types returned will not be demangled, default: false.
27✔
1500
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1501
   */
27✔
1502
  getTopicNamesAndTypes(noDemangle = false) {
27✔
1503
    return rclnodejs.getTopicNamesAndTypes(this.handle, noDemangle);
×
UNCOV
1504
  }
×
1505

27✔
1506
  /**
27✔
1507
   * Get the list of services discovered by the provided node.
27✔
1508
   * @return {Array<{name: string, types: Array<string>}>} - An array of the names and types.
27✔
1509
   */
27✔
1510
  getServiceNamesAndTypes() {
27✔
1511
    return rclnodejs.getServiceNamesAndTypes(this.handle);
2✔
1512
  }
2✔
1513

27✔
1514
  /**
27✔
1515
   * Return a list of publishers on a given topic.
27✔
1516
   *
27✔
1517
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
27✔
1518
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
27✔
1519
   *
27✔
1520
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
27✔
1521
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
27✔
1522
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
27✔
1523
   * follow ROS topic name conventions.
27✔
1524
   *
27✔
1525
   * `topic` may be a relative, private, or fully qualified topic name.
27✔
1526
   *  A relative or private topic will be expanded using this node's namespace and name.
27✔
1527
   *  The queried `topic` is not remapped.
27✔
1528
   *
27✔
1529
   * @param {string} topic - The topic on which to find the publishers.
27✔
1530
   * @param {boolean} [noDemangle=false] - If `true`, `topic` needs to be a valid middleware topic
27✔
1531
   *                               name, otherwise it should be a valid ROS topic name. Defaults to `false`.
27✔
1532
   * @returns {Array} - list of publishers
27✔
1533
   */
27✔
1534
  getPublishersInfoByTopic(topic, noDemangle = false) {
27✔
1535
    return rclnodejs.getPublishersInfoByTopic(
4✔
1536
      this.handle,
4✔
1537
      this._getValidatedTopic(topic, noDemangle),
4✔
1538
      noDemangle
4✔
1539
    );
4✔
1540
  }
4✔
1541

27✔
1542
  /**
27✔
1543
   * Return a list of subscriptions on a given topic.
27✔
1544
   *
27✔
1545
   * The returned parameter is a list of TopicEndpointInfo objects, where each will contain
27✔
1546
   * the node name, node namespace, topic type, topic endpoint's GID, and its QoS profile.
27✔
1547
   *
27✔
1548
   * When the `no_mangle` parameter is `true`, the provided `topic` should be a valid
27✔
1549
   * topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
27✔
1550
   * apps).  When the `no_mangle` parameter is `false`, the provided `topic` should
27✔
1551
   * follow ROS topic name conventions.
27✔
1552
   *
27✔
1553
   * `topic` may be a relative, private, or fully qualified topic name.
27✔
1554
   *  A relative or private topic will be expanded using this node's namespace and name.
27✔
1555
   *  The queried `topic` is not remapped.
27✔
1556
   *
27✔
1557
   * @param {string} topic - The topic on which to find the subscriptions.
27✔
1558
   * @param {boolean} [noDemangle=false] -  If `true`, `topic` needs to be a valid middleware topic
27✔
1559
                                    name, otherwise it should be a valid ROS topic name. Defaults to `false`.
27✔
1560
   * @returns {Array} - list of subscriptions
27✔
1561
   */
27✔
1562
  getSubscriptionsInfoByTopic(topic, noDemangle = false) {
27✔
1563
    return rclnodejs.getSubscriptionsInfoByTopic(
2✔
1564
      this.handle,
2✔
1565
      this._getValidatedTopic(topic, noDemangle),
2✔
1566
      noDemangle
2✔
1567
    );
2✔
1568
  }
2✔
1569

27✔
1570
  /**
27✔
1571
   * Return a list of clients on a given service.
27✔
1572
   *
27✔
1573
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
27✔
1574
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
27✔
1575
   *
27✔
1576
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
27✔
1577
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
27✔
1578
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
27✔
1579
   * follow ROS service name conventions.
27✔
1580
   *
27✔
1581
   * `service` may be a relative, private, or fully qualified service name.
27✔
1582
   *  A relative or private service will be expanded using this node's namespace and name.
27✔
1583
   *  The queried `service` is not remapped.
27✔
1584
   *
27✔
1585
   * @param {string} service - The service on which to find the clients.
27✔
1586
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
27✔
1587
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
27✔
1588
   * @returns {Array} - list of clients
27✔
1589
   */
27✔
1590
  getClientsInfoByService(service, noDemangle = false) {
27✔
1591
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.LYRICAL) {
2!
1592
      console.warn(
×
UNCOV
1593
        'getClientsInfoByService is not supported by this version of ROS 2'
×
UNCOV
1594
      );
×
1595
      return null;
×
UNCOV
1596
    }
×
1597
    return rclnodejs.getClientsInfoByService(
2✔
1598
      this.handle,
2✔
1599
      this._getValidatedServiceName(service, noDemangle),
2✔
1600
      noDemangle
2✔
1601
    );
2✔
1602
  }
2✔
1603

27✔
1604
  /**
27✔
1605
   * Return a list of servers on a given service.
27✔
1606
   *
27✔
1607
   * The returned parameter is a list of ServiceEndpointInfo objects, where each will contain
27✔
1608
   * the node name, node namespace, service type, service endpoint's GID, and its QoS profile.
27✔
1609
   *
27✔
1610
   * When the `no_mangle` parameter is `true`, the provided `service` should be a valid
27✔
1611
   * service name for the middleware (useful when combining ROS with native middleware (e.g. DDS)
27✔
1612
   * apps).  When the `no_mangle` parameter is `false`, the provided `service` should
27✔
1613
   * follow ROS service name conventions.
27✔
1614
   *
27✔
1615
   * `service` may be a relative, private, or fully qualified service name.
27✔
1616
   *  A relative or private service will be expanded using this node's namespace and name.
27✔
1617
   *  The queried `service` is not remapped.
27✔
1618
   *
27✔
1619
   * @param {string} service - The service on which to find the servers.
27✔
1620
   * @param {boolean} [noDemangle=false] - If `true`, `service` needs to be a valid middleware service
27✔
1621
   *                               name, otherwise it should be a valid ROS service name. Defaults to `false`.
27✔
1622
   * @returns {Array} - list of servers
27✔
1623
   */
27✔
1624
  getServersInfoByService(service, noDemangle = false) {
27✔
1625
    if (DistroUtils.getDistroId() < DistroUtils.DistroId.LYRICAL) {
2!
1626
      console.warn(
×
UNCOV
1627
        'getServersInfoByService is not supported by this version of ROS 2'
×
UNCOV
1628
      );
×
1629
      return null;
×
UNCOV
1630
    }
×
1631
    return rclnodejs.getServersInfoByService(
2✔
1632
      this.handle,
2✔
1633
      this._getValidatedServiceName(service, noDemangle),
2✔
1634
      noDemangle
2✔
1635
    );
2✔
1636
  }
2✔
1637

27✔
1638
  /**
27✔
1639
   * Get the list of nodes discovered by the provided node.
27✔
1640
   * @return {Array<string>} - An array of the names.
27✔
1641
   */
27✔
1642
  getNodeNames() {
27✔
1643
    return this.getNodeNamesAndNamespaces().map((item) => item.name);
15✔
1644
  }
15✔
1645

27✔
1646
  /**
27✔
1647
   * Get the list of nodes and their namespaces discovered by the provided node.
27✔
1648
   * @return {Array<{name: string, namespace: string}>} An array of the names and namespaces.
27✔
1649
   */
27✔
1650
  getNodeNamesAndNamespaces() {
27✔
1651
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ false);
17✔
1652
  }
17✔
1653

27✔
1654
  /**
27✔
1655
   * Get the list of nodes and their namespaces with enclaves discovered by the provided node.
27✔
1656
   * @return {Array<{name: string, namespace: string, enclave: string}>} An array of the names, namespaces and enclaves.
27✔
1657
   */
27✔
1658
  getNodeNamesAndNamespacesWithEnclaves() {
27✔
1659
    return rclnodejs.getNodeNames(this.handle, /*getEnclaves=*/ true);
1✔
1660
  }
1✔
1661

27✔
1662
  /**
27✔
1663
   * Return the number of publishers on a given topic.
27✔
1664
   * @param {string} topic - The name of the topic.
27✔
1665
   * @returns {number} - Number of publishers on the given topic.
27✔
1666
   */
27✔
1667
  countPublishers(topic) {
27✔
1668
    let expandedTopic = rclnodejs.expandTopicName(
8✔
1669
      topic,
8✔
1670
      this.name(),
8✔
1671
      this.namespace()
8✔
1672
    );
8✔
1673
    rclnodejs.validateTopicName(expandedTopic);
8✔
1674

8✔
1675
    return rclnodejs.countPublishers(this.handle, expandedTopic);
8✔
1676
  }
8✔
1677

27✔
1678
  /**
27✔
1679
   * Return the number of subscribers on a given topic.
27✔
1680
   * @param {string} topic - The name of the topic.
27✔
1681
   * @returns {number} - Number of subscribers on the given topic.
27✔
1682
   */
27✔
1683
  countSubscribers(topic) {
27✔
1684
    let expandedTopic = rclnodejs.expandTopicName(
6✔
1685
      topic,
6✔
1686
      this.name(),
6✔
1687
      this.namespace()
6✔
1688
    );
6✔
1689
    rclnodejs.validateTopicName(expandedTopic);
6✔
1690

6✔
1691
    return rclnodejs.countSubscribers(this.handle, expandedTopic);
6✔
1692
  }
6✔
1693

27✔
1694
  /**
27✔
1695
   * Get the number of clients on a given service name.
27✔
1696
   * @param {string} serviceName - the service name
27✔
1697
   * @returns {Number}
27✔
1698
   */
27✔
1699
  countClients(serviceName) {
27✔
1700
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
2!
1701
      console.warn('countClients is not supported by this version of ROS 2');
×
1702
      return null;
×
UNCOV
1703
    }
×
1704
    return rclnodejs.countClients(this.handle, serviceName);
2✔
1705
  }
2✔
1706

27✔
1707
  /**
27✔
1708
   * Get the number of services on a given service name.
27✔
1709
   * @param {string} serviceName - the service name
27✔
1710
   * @returns {Number}
27✔
1711
   */
27✔
1712
  countServices(serviceName) {
27✔
1713
    if (DistroUtils.getDistroId() <= DistroUtils.getDistroId('humble')) {
1!
1714
      console.warn('countServices is not supported by this version of ROS 2');
×
1715
      return null;
×
UNCOV
1716
    }
×
1717
    return rclnodejs.countServices(this.handle, serviceName);
1✔
1718
  }
1✔
1719

27✔
1720
  /**
27✔
1721
   * Get the list of parameter-overrides found on the commandline and
27✔
1722
   * in the NodeOptions.parameter_overrides property.
27✔
1723
   *
27✔
1724
   * @return {Array<Parameter>} - An array of Parameters.
27✔
1725
   */
27✔
1726
  getParameterOverrides() {
27✔
1727
    return Array.from(this._parameterOverrides.values());
8✔
1728
  }
8✔
1729

27✔
1730
  /**
27✔
1731
   * Declare a parameter.
27✔
1732
   *
27✔
1733
   * Internally, register a parameter and it's descriptor.
27✔
1734
   * If a parameter-override exists, it's value will replace that of the parameter
27✔
1735
   * unless ignoreOverride is true.
27✔
1736
   * If the descriptor is undefined, then a ParameterDescriptor will be inferred
27✔
1737
   * from the parameter's state.
27✔
1738
   *
27✔
1739
   * If a parameter by the same name has already been declared then an Error is thrown.
27✔
1740
   * A parameter must be undeclared before attempting to redeclare it.
27✔
1741
   *
27✔
1742
   * @param {Parameter} parameter - Parameter to declare.
27✔
1743
   * @param {ParameterDescriptor} [descriptor] - Optional descriptor for parameter.
27✔
1744
   * @param {boolean} [ignoreOverride] - When true disregard any parameter-override that may be present.
27✔
1745
   * @return {Parameter} - The newly declared parameter.
27✔
1746
   */
27✔
1747
  declareParameter(parameter, descriptor, ignoreOverride = false) {
27✔
1748
    const parameters = this.declareParameters(
2,535✔
1749
      [parameter],
2,535✔
1750
      descriptor ? [descriptor] : [],
2,535✔
1751
      ignoreOverride
2,535✔
1752
    );
2,535✔
1753
    return parameters.length == 1 ? parameters[0] : null;
2,535!
1754
  }
2,535✔
1755

27✔
1756
  /**
27✔
1757
   * Declare a list of parameters.
27✔
1758
   *
27✔
1759
   * Internally register parameters with their corresponding descriptor one by one
27✔
1760
   * in the order they are provided. This is an atomic operation. If an error
27✔
1761
   * occurs the process halts and no further parameters are declared.
27✔
1762
   * Parameters that have already been processed are undeclared.
27✔
1763
   *
27✔
1764
   * While descriptors is an optional parameter, when provided there must be
27✔
1765
   * a descriptor for each parameter; otherwise an Error is thrown.
27✔
1766
   * If descriptors is not provided then a descriptor will be inferred
27✔
1767
   * from each parameter's state.
27✔
1768
   *
27✔
1769
   * When a parameter-override is available, the parameter's value
27✔
1770
   * will be replaced with that of the parameter-override unless ignoreOverrides
27✔
1771
   * is true.
27✔
1772
   *
27✔
1773
   * If a parameter by the same name has already been declared then an Error is thrown.
27✔
1774
   * A parameter must be undeclared before attempting to redeclare it.
27✔
1775
   *
27✔
1776
   * Prior to declaring the parameters each SetParameterEventCallback registered
27✔
1777
   * using setOnParameterEventCallback() is called in succession with the parameters
27✔
1778
   * list. Any SetParameterEventCallback that retuns does not return a successful
27✔
1779
   * result will cause the entire operation to terminate with no changes to the
27✔
1780
   * parameters. When all SetParameterEventCallbacks return successful then the
27✔
1781
   * list of parameters is updated.
27✔
1782
   *
27✔
1783
   * @param {Parameter[]} parameters - The parameters to declare.
27✔
1784
   * @param {ParameterDescriptor[]} [descriptors] - Optional descriptors,
27✔
1785
   *    a 1-1 correspondence with parameters.
27✔
1786
   * @param {boolean} ignoreOverrides - When true, parameter-overrides are
27✔
1787
   *    not considered, i.e.,ignored.
27✔
1788
   * @return {Parameter[]} - The declared parameters.
27✔
1789
   */
27✔
1790
  declareParameters(parameters, descriptors = [], ignoreOverrides = false) {
27✔
1791
    if (!Array.isArray(parameters)) {
2,535!
1792
      throw new TypeValidationError('parameters', parameters, 'Array', {
×
UNCOV
1793
        nodeName: this.name(),
×
UNCOV
1794
      });
×
UNCOV
1795
    }
×
1796
    if (!Array.isArray(descriptors)) {
2,535!
1797
      throw new TypeValidationError('descriptors', descriptors, 'Array', {
×
UNCOV
1798
        nodeName: this.name(),
×
UNCOV
1799
      });
×
UNCOV
1800
    }
×
1801
    if (descriptors.length > 0 && parameters.length !== descriptors.length) {
2,535!
1802
      throw new ValidationError(
×
UNCOV
1803
        'Each parameter must have a corresponding ParameterDescriptor',
×
UNCOV
1804
        {
×
UNCOV
1805
          code: 'PARAMETER_DESCRIPTOR_MISMATCH',
×
UNCOV
1806
          argumentName: 'descriptors',
×
UNCOV
1807
          providedValue: descriptors.length,
×
UNCOV
1808
          expectedType: `Array with length ${parameters.length}`,
×
UNCOV
1809
          nodeName: this.name(),
×
UNCOV
1810
        }
×
UNCOV
1811
      );
×
UNCOV
1812
    }
×
1813

2,535✔
1814
    const declaredDescriptors = [];
2,535✔
1815
    const declaredParameters = [];
2,535✔
1816
    const declaredParameterCollisions = [];
2,535✔
1817
    for (let i = 0; i < parameters.length; i++) {
2,535✔
1818
      let parameter =
2,535✔
1819
        !ignoreOverrides && this._parameterOverrides.has(parameters[i].name)
2,535✔
1820
          ? this._parameterOverrides.get(parameters[i].name)
2,535✔
1821
          : parameters[i];
2,535✔
1822

2,535✔
1823
      // stop processing parameters that have already been declared
2,535✔
1824
      if (this._parameters.has(parameter.name)) {
2,535!
1825
        declaredParameterCollisions.push(parameter);
×
1826
        continue;
×
UNCOV
1827
      }
×
1828

2,535✔
1829
      // create descriptor for parameter if not provided
2,535✔
1830
      let descriptor =
2,535✔
1831
        descriptors.length > 0
2,535✔
1832
          ? descriptors[i]
2,535✔
1833
          : ParameterDescriptor.fromParameter(parameter);
2,535✔
1834

2,535✔
1835
      descriptor.validate();
2,535✔
1836

2,535✔
1837
      declaredDescriptors.push(descriptor);
2,535✔
1838
      declaredParameters.push(parameter);
2,535✔
1839
    }
2,535✔
1840

2,535✔
1841
    if (declaredParameterCollisions.length > 0) {
2,535!
UNCOV
1842
      const errorMsg =
×
1843
        declaredParameterCollisions.length == 1
×
UNCOV
1844
          ? `Parameter(${declaredParameterCollisions[0]}) already declared.`
×
UNCOV
1845
          : `Multiple parameters already declared, e.g., Parameter(${declaredParameterCollisions[0]}).`;
×
1846
      throw new Error(errorMsg);
×
UNCOV
1847
    }
×
1848

2,535✔
1849
    // register descriptor
2,535✔
1850
    for (const descriptor of declaredDescriptors) {
2,535✔
1851
      this._parameterDescriptors.set(descriptor.name, descriptor);
2,535✔
1852
    }
2,535✔
1853

2,535✔
1854
    const result = this._setParametersAtomically(declaredParameters, true);
2,535✔
1855
    if (!result.successful) {
2,535!
UNCOV
1856
      // unregister descriptors
×
1857
      for (const descriptor of declaredDescriptors) {
×
1858
        this._parameterDescriptors.delete(descriptor.name);
×
UNCOV
1859
      }
×
UNCOV
1860

×
1861
      throw new Error(result.reason);
×
UNCOV
1862
    }
×
1863

2,535✔
1864
    return this.getParameters(declaredParameters.map((param) => param.name));
2,535✔
1865
  }
2,535✔
1866

27✔
1867
  /**
27✔
1868
   * Undeclare a parameter.
27✔
1869
   *
27✔
1870
   * Readonly parameters can not be undeclared or updated.
27✔
1871
   * @param {string} name - Name of parameter to undeclare.
27✔
1872
   * @return {undefined} -
27✔
1873
   */
27✔
1874
  undeclareParameter(name) {
27✔
1875
    if (!this.hasParameter(name)) return;
1!
1876

1✔
1877
    const descriptor = this.getParameterDescriptor(name);
1✔
1878
    if (descriptor.readOnly) {
1!
1879
      throw new Error(
×
UNCOV
1880
        `${name} parameter is read-only and can not be undeclared`
×
UNCOV
1881
      );
×
UNCOV
1882
    }
×
1883

1✔
1884
    this._parameters.delete(name);
1✔
1885
    this._parameterDescriptors.delete(name);
1✔
1886
  }
1✔
1887

27✔
1888
  /**
27✔
1889
   * Determine if a parameter has been declared.
27✔
1890
   * @param {string} name - name of parameter
27✔
1891
   * @returns {boolean} - Return true if parameter is declared; false otherwise.
27✔
1892
   */
27✔
1893
  hasParameter(name) {
27✔
1894
    return this._parameters.has(name);
6,362✔
1895
  }
6,362✔
1896

27✔
1897
  /**
27✔
1898
   * Get a declared parameter by name.
27✔
1899
   *
27✔
1900
   * If unable to locate a declared parameter then a
27✔
1901
   * parameter with type == PARAMETER_NOT_SET is returned.
27✔
1902
   *
27✔
1903
   * @param {string} name - The name of the parameter.
27✔
1904
   * @return {Parameter} - The parameter.
27✔
1905
   */
27✔
1906
  getParameter(name) {
27✔
1907
    return this.getParameters([name])[0];
1,900✔
1908
  }
1,900✔
1909

27✔
1910
  /**
27✔
1911
   * Get a list of parameters.
27✔
1912
   *
27✔
1913
   * Find and return the declared parameters.
27✔
1914
   * If no names are provided return all declared parameters.
27✔
1915
   *
27✔
1916
   * If unable to locate a declared parameter then a
27✔
1917
   * parameter with type == PARAMETER_NOT_SET is returned in
27✔
1918
   * it's place.
27✔
1919
   *
27✔
1920
   * @param {string[]} [names] - The names of the declared parameters
27✔
1921
   *    to find or null indicating to return all declared parameters.
27✔
1922
   * @return {Parameter[]} - The parameters.
27✔
1923
   */
27✔
1924
  getParameters(names = []) {
27✔
1925
    let params = [];
4,473✔
1926

4,473✔
1927
    if (names.length == 0) {
4,473✔
1928
      // get all parameters
12✔
1929
      params = [...this._parameters.values()];
12✔
1930
      return params;
12✔
1931
    }
12✔
1932

4,461✔
1933
    for (const name of names) {
4,473✔
1934
      const param = this.hasParameter(name)
4,468✔
1935
        ? this._parameters.get(name)
4,468✔
1936
        : new Parameter(name, ParameterType.PARAMETER_NOT_SET);
4,468✔
1937

4,468✔
1938
      params.push(param);
4,468✔
1939
    }
4,468✔
1940

4,461✔
1941
    return params;
4,461✔
1942
  }
4,473✔
1943

27✔
1944
  /**
27✔
1945
   * Get the types of given parameters.
27✔
1946
   *
27✔
1947
   * Return the types of given parameters.
27✔
1948
   *
27✔
1949
   * @param {string[]} [names] - The names of the declared parameters.
27✔
1950
   * @return {Uint8Array} - The types.
27✔
1951
   */
27✔
1952
  getParameterTypes(names = []) {
27✔
1953
    let types = [];
3✔
1954

3✔
1955
    for (const name of names) {
3✔
1956
      const descriptor = this._parameterDescriptors.get(name);
7✔
1957
      if (descriptor) {
7✔
1958
        types.push(descriptor.type);
7✔
1959
      }
7✔
1960
    }
7✔
1961
    return types;
3✔
1962
  }
3✔
1963

27✔
1964
  /**
27✔
1965
   * Get the names of all declared parameters.
27✔
1966
   *
27✔
1967
   * @return {Array<string>} - The declared parameter names or empty array if
27✔
1968
   *    no parameters have been declared.
27✔
1969
   */
27✔
1970
  getParameterNames() {
27✔
1971
    return this.getParameters().map((param) => param.name);
7✔
1972
  }
7✔
1973

27✔
1974
  /**
27✔
1975
   * Determine if a parameter descriptor exists.
27✔
1976
   *
27✔
1977
   * @param {string} name - The name of a descriptor to for.
27✔
1978
   * @return {boolean} - true if a descriptor has been declared; otherwise false.
27✔
1979
   */
27✔
1980
  hasParameterDescriptor(name) {
27✔
1981
    return !!this.getParameterDescriptor(name);
2,574✔
1982
  }
2,574✔
1983

27✔
1984
  /**
27✔
1985
   * Get a declared parameter descriptor by name.
27✔
1986
   *
27✔
1987
   * If unable to locate a declared parameter descriptor then a
27✔
1988
   * descriptor with type == PARAMETER_NOT_SET is returned.
27✔
1989
   *
27✔
1990
   * @param {string} name - The name of the parameter descriptor to find.
27✔
1991
   * @return {ParameterDescriptor} - The parameter descriptor.
27✔
1992
   */
27✔
1993
  getParameterDescriptor(name) {
27✔
1994
    return this.getParameterDescriptors([name])[0];
5,149✔
1995
  }
5,149✔
1996

27✔
1997
  /**
27✔
1998
   * Find a list of declared ParameterDescriptors.
27✔
1999
   *
27✔
2000
   * If no names are provided return all declared descriptors.
27✔
2001
   *
27✔
2002
   * If unable to locate a declared descriptor then a
27✔
2003
   * descriptor with type == PARAMETER_NOT_SET is returned in
27✔
2004
   * it's place.
27✔
2005
   *
27✔
2006
   * @param {string[]} [names] - The names of the declared parameter
27✔
2007
   *    descriptors to find or null indicating to return all declared descriptors.
27✔
2008
   * @return {ParameterDescriptor[]} - The parameter descriptors.
27✔
2009
   */
27✔
2010
  getParameterDescriptors(names = []) {
27✔
2011
    let descriptors = [];
5,152✔
2012

5,152✔
2013
    if (names.length == 0) {
5,152!
UNCOV
2014
      // get all parameters
×
2015
      descriptors = [...this._parameterDescriptors.values()];
×
2016
      return descriptors;
×
UNCOV
2017
    }
×
2018

5,152✔
2019
    for (const name of names) {
5,152✔
2020
      let descriptor = this._parameterDescriptors.get(name);
5,154✔
2021
      if (!descriptor) {
5,154!
2022
        descriptor = new ParameterDescriptor(
×
UNCOV
2023
          name,
×
UNCOV
2024
          ParameterType.PARAMETER_NOT_SET
×
UNCOV
2025
        );
×
UNCOV
2026
      }
×
2027
      descriptors.push(descriptor);
5,154✔
2028
    }
5,154✔
2029

5,152✔
2030
    return descriptors;
5,152✔
2031
  }
5,152✔
2032

27✔
2033
  /**
27✔
2034
   * Replace a declared parameter.
27✔
2035
   *
27✔
2036
   * The parameter being replaced must be a declared parameter who's descriptor
27✔
2037
   * is not readOnly; otherwise an Error is thrown.
27✔
2038
   *
27✔
2039
   * @param {Parameter} parameter - The new parameter.
27✔
2040
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - The result of the operation.
27✔
2041
   */
27✔
2042
  setParameter(parameter) {
27✔
2043
    const results = this.setParameters([parameter]);
26✔
2044
    return results[0];
26✔
2045
  }
26✔
2046

27✔
2047
  /**
27✔
2048
   * Replace a list of declared parameters.
27✔
2049
   *
27✔
2050
   * Declared parameters are replaced in the order they are provided and
27✔
2051
   * a ParameterEvent is published for each individual parameter change.
27✔
2052
   *
27✔
2053
   * Prior to setting the parameters each SetParameterEventCallback registered
27✔
2054
   * using setOnParameterEventCallback() is called in succession with the parameters
27✔
2055
   * list. Any SetParameterEventCallback that retuns does not return a successful
27✔
2056
   * result will cause the entire operation to terminate with no changes to the
27✔
2057
   * parameters. When all SetParameterEventCallbacks return successful then the
27✔
2058
   * list of parameters is updated.
27✔
2059
   *
27✔
2060
   * If an error occurs, the process is stopped and returned. Parameters
27✔
2061
   * set before an error remain unchanged.
27✔
2062
   *
27✔
2063
   * @param {Parameter[]} parameters - The parameters to set.
27✔
2064
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult[]} - A list of SetParameterResult, one for each parameter that was set.
27✔
2065
   */
27✔
2066
  setParameters(parameters = []) {
27✔
2067
    return parameters.map((parameter) =>
37✔
2068
      this.setParametersAtomically([parameter])
40✔
2069
    );
37✔
2070
  }
37✔
2071

27✔
2072
  /**
27✔
2073
   * Repalce a list of declared parameters atomically.
27✔
2074
   *
27✔
2075
   * Declared parameters are replaced in the order they are provided.
27✔
2076
   * A single ParameterEvent is published collectively for all changed
27✔
2077
   * parameters.
27✔
2078
   *
27✔
2079
   * Prior to setting the parameters each SetParameterEventCallback registered
27✔
2080
   * using setOnParameterEventCallback() is called in succession with the parameters
27✔
2081
   * list. Any SetParameterEventCallback that retuns does not return a successful
27✔
2082
   * result will cause the entire operation to terminate with no changes to the
27✔
2083
   * parameters. When all SetParameterEventCallbacks return successful then the
27✔
2084
   * list of parameters is updated.d
27✔
2085
   *
27✔
2086
   * If an error occurs, the process stops immediately. All parameters updated to
27✔
2087
   * the point of the error are reverted to their previous state.
27✔
2088
   *
27✔
2089
   * @param {Parameter[]} parameters - The parameters to set.
27✔
2090
   * @return {rclnodejs.rcl_interfaces.msg.SetParameterResult} - describes the result of setting 1 or more parameters.
27✔
2091
   */
27✔
2092
  setParametersAtomically(parameters = []) {
27✔
2093
    return this._setParametersAtomically(parameters);
41✔
2094
  }
41✔
2095

27✔
2096
  /**
27✔
2097
   * Internal method for updating parameters atomically.
27✔
2098
   *
27✔
2099
   * Prior to setting the parameters each SetParameterEventCallback registered
27✔
2100
   * using setOnParameterEventCallback() is called in succession with the parameters
27✔
2101
   * list. Any SetParameterEventCallback that retuns does not return a successful
27✔
2102
   * result will cause the entire operation to terminate with no changes to the
27✔
2103
   * parameters. When all SetParameterEventCallbacks return successful then the
27✔
2104
   * list of parameters is updated.
27✔
2105
   *
27✔
2106
   * @param {Paramerter[]} parameters - The parameters to update.
27✔
2107
   * @param {boolean} declareParameterMode - When true parameters are being declared;
27✔
2108
   *    otherwise they are being changed.
27✔
2109
   * @return {SetParameterResult} - A single collective result.
27✔
2110
   */
27✔
2111
  _setParametersAtomically(parameters = [], declareParameterMode = false) {
27✔
2112
    // 1) PRE callbacks — pipeline: each callback receives the output of the previous
2,576✔
2113
    if (this._preSetParametersCallbacks.length > 0) {
2,576✔
2114
      for (const callback of this._preSetParametersCallbacks) {
6✔
2115
        const result = callback(parameters);
7✔
2116
        if (!Array.isArray(result)) {
7!
2117
          return {
×
UNCOV
2118
            successful: false,
×
UNCOV
2119
            reason:
×
UNCOV
2120
              'pre-set parameters callback must return an array of Parameters',
×
UNCOV
2121
          };
×
UNCOV
2122
        }
×
2123
        parameters = result;
7✔
2124
        if (parameters.length === 0) {
7✔
2125
          return {
2✔
2126
            successful: false,
2✔
2127
            reason:
2✔
2128
              'parameter list is empty after pre-set callback; set rejected',
2✔
2129
          };
2✔
2130
        }
2✔
2131
      }
7✔
2132
    }
4✔
2133

2,574✔
2134
    // 2) Validate
2,574✔
2135
    let result = this._validateParameters(parameters, declareParameterMode);
2,574✔
2136
    if (!result.successful) {
2,576!
2137
      return result;
×
UNCOV
2138
    }
×
2139

2,574✔
2140
    // give all SetParametersCallbacks a chance to veto this change
2,574✔
2141
    for (const callback of this._setParametersCallbacks) {
2,576✔
2142
      result = callback(parameters);
1,647✔
2143
      if (!result.successful) {
1,647✔
2144
        // a callback has vetoed a parameter change
3✔
2145
        return result;
3✔
2146
      }
3✔
2147
    }
1,647✔
2148

2,571✔
2149
    // collectively track updates to parameters for use
2,571✔
2150
    // when publishing a ParameterEvent
2,571✔
2151
    const newParameters = [];
2,571✔
2152
    const changedParameters = [];
2,571✔
2153
    const deletedParameters = [];
2,571✔
2154

2,571✔
2155
    for (const parameter of parameters) {
2,571✔
2156
      if (parameter.type == ParameterType.PARAMETER_NOT_SET) {
2,571✔
2157
        this.undeclareParameter(parameter.name);
1✔
2158
        deletedParameters.push(parameter);
1✔
2159
      } else {
2,571✔
2160
        this._parameters.set(parameter.name, parameter);
2,570✔
2161
        if (declareParameterMode) {
2,570✔
2162
          newParameters.push(parameter);
2,535✔
2163
        } else {
2,570✔
2164
          changedParameters.push(parameter);
35✔
2165
        }
35✔
2166
      }
2,570✔
2167
    }
2,571✔
2168

2,571✔
2169
    // create ParameterEvent
2,571✔
2170
    const parameterEvent = new (loader.loadInterface(
2,571✔
2171
      PARAMETER_EVENT_MSG_TYPE
2,571✔
2172
    ))();
2,571✔
2173

2,571✔
2174
    const { seconds, nanoseconds } = this._clock.now().secondsAndNanoseconds;
2,571✔
2175
    parameterEvent.stamp = {
2,571✔
2176
      sec: Number(seconds),
2,571✔
2177
      nanosec: Number(nanoseconds),
2,571✔
2178
    };
2,571✔
2179

2,571✔
2180
    parameterEvent.node =
2,571✔
2181
      this.namespace() === '/'
2,571✔
2182
        ? this.namespace() + this.name()
2,576✔
2183
        : this.namespace() + '/' + this.name();
2,576✔
2184

2,576✔
2185
    if (newParameters.length > 0) {
2,576✔
2186
      parameterEvent['new_parameters'] = newParameters.map((parameter) =>
2,535✔
2187
        parameter.toParameterMessage()
2,535✔
2188
      );
2,535✔
2189
    }
2,535✔
2190
    if (changedParameters.length > 0) {
2,576✔
2191
      parameterEvent['changed_parameters'] = changedParameters.map(
35✔
2192
        (parameter) => parameter.toParameterMessage()
35✔
2193
      );
35✔
2194
    }
35✔
2195
    if (deletedParameters.length > 0) {
2,576✔
2196
      parameterEvent['deleted_parameters'] = deletedParameters.map(
1✔
2197
        (parameter) => parameter.toParameterMessage()
1✔
2198
      );
1✔
2199
    }
1✔
2200

2,571✔
2201
    // Publish ParameterEvent.
2,571✔
2202
    this._parameterEventPublisher.publish(parameterEvent);
2,571✔
2203

2,571✔
2204
    // POST callbacks — for side effects after successful set
2,571✔
2205
    for (const callback of this._postSetParametersCallbacks) {
2,576✔
2206
      callback(parameters);
4✔
2207
    }
4✔
2208

2,571✔
2209
    return {
2,571✔
2210
      successful: true,
2,571✔
2211
      reason: '',
2,571✔
2212
    };
2,571✔
2213
  }
2,576✔
2214

27✔
2215
  /**
27✔
2216
   * This callback is called when declaring a parameter or setting a parameter.
27✔
2217
   * The callback is provided a list of parameters and returns a SetParameterResult
27✔
2218
   * to indicate approval or veto of the operation.
27✔
2219
   *
27✔
2220
   * @callback SetParametersCallback
27✔
2221
   * @param {Parameter[]} parameters - The message published
27✔
2222
   * @returns {rcl_interfaces.msg.SetParameterResult} -
27✔
2223
   *
27✔
2224
   * @see [Node.addOnSetParametersCallback]{@link Node#addOnSetParametersCallback}
27✔
2225
   * @see [Node.removeOnSetParametersCallback]{@link Node#removeOnSetParametersCallback}
27✔
2226
   */
27✔
2227

27✔
2228
  /**
27✔
2229
   * Add a callback to the front of the list of callbacks invoked for parameter declaration
27✔
2230
   * and setting. No checks are made for duplicate callbacks.
27✔
2231
   *
27✔
2232
   * @param {SetParametersCallback} callback - The callback to add.
27✔
2233
   * @returns {undefined}
27✔
2234
   */
27✔
2235
  addOnSetParametersCallback(callback) {
27✔
2236
    this._setParametersCallbacks.unshift(callback);
956✔
2237
  }
956✔
2238

27✔
2239
  /**
27✔
2240
   * Remove a callback from the list of SetParametersCallbacks.
27✔
2241
   * If the callback is not found the process is a nop.
27✔
2242
   *
27✔
2243
   * @param {SetParametersCallback} callback - The callback to be removed
27✔
2244
   * @returns {undefined}
27✔
2245
   */
27✔
2246
  removeOnSetParametersCallback(callback) {
27✔
2247
    const idx = this._setParametersCallbacks.indexOf(callback);
2✔
2248
    if (idx > -1) {
2✔
2249
      this._setParametersCallbacks.splice(idx, 1);
2✔
2250
    }
2✔
2251
  }
2✔
2252

27✔
2253
  /**
27✔
2254
   * A callback invoked before parameter validation and setting.
27✔
2255
   * It receives the parameter list and must return a (possibly modified) parameter list.
27✔
2256
   *
27✔
2257
   * @callback PreSetParametersCallback
27✔
2258
   * @param {Parameter[]} parameters - The parameters about to be set.
27✔
2259
   * @returns {Parameter[]} - The modified parameter list to proceed with.
27✔
2260
   *
27✔
2261
   * @see [Node.addPreSetParametersCallback]{@link Node#addPreSetParametersCallback}
27✔
2262
   * @see [Node.removePreSetParametersCallback]{@link Node#removePreSetParametersCallback}
27✔
2263
   */
27✔
2264

27✔
2265
  /**
27✔
2266
   * Add a callback invoked before parameter validation.
27✔
2267
   * The callback receives the parameter list and must return a (possibly modified)
27✔
2268
   * parameter list. This can be used to coerce, add, or remove parameters before
27✔
2269
   * they are validated and applied. If any pre-set callback returns an empty list,
27✔
2270
   * the set is rejected.
27✔
2271
   *
27✔
2272
   * @param {PreSetParametersCallback} callback - The callback to add.
27✔
2273
   * @returns {undefined}
27✔
2274
   */
27✔
2275
  addPreSetParametersCallback(callback) {
27✔
2276
    this._preSetParametersCallbacks.unshift(callback);
8✔
2277
  }
8✔
2278

27✔
2279
  /**
27✔
2280
   * Remove a pre-set parameters callback.
27✔
2281
   *
27✔
2282
   * @param {PreSetParametersCallback} callback - The callback to remove.
27✔
2283
   * @returns {undefined}
27✔
2284
   */
27✔
2285
  removePreSetParametersCallback(callback) {
27✔
2286
    const idx = this._preSetParametersCallbacks.indexOf(callback);
1✔
2287
    if (idx > -1) {
1✔
2288
      this._preSetParametersCallbacks.splice(idx, 1);
1✔
2289
    }
1✔
2290
  }
1✔
2291

27✔
2292
  /**
27✔
2293
   * A callback invoked after parameters have been successfully set.
27✔
2294
   * It receives the final parameter list. For side effects only (return value is ignored).
27✔
2295
   *
27✔
2296
   * @callback PostSetParametersCallback
27✔
2297
   * @param {Parameter[]} parameters - The parameters that were set.
27✔
2298
   * @returns {undefined}
27✔
2299
   *
27✔
2300
   * @see [Node.addPostSetParametersCallback]{@link Node#addPostSetParametersCallback}
27✔
2301
   * @see [Node.removePostSetParametersCallback]{@link Node#removePostSetParametersCallback}
27✔
2302
   */
27✔
2303

27✔
2304
  /**
27✔
2305
   * Add a callback invoked after parameters are successfully set.
27✔
2306
   * The callback receives the final parameter list. Useful for triggering
27✔
2307
   * side effects (e.g., reconfiguring a component when a parameter changes).
27✔
2308
   *
27✔
2309
   * @param {PostSetParametersCallback} callback - The callback to add.
27✔
2310
   * @returns {undefined}
27✔
2311
   */
27✔
2312
  addPostSetParametersCallback(callback) {
27✔
2313
    this._postSetParametersCallbacks.unshift(callback);
8✔
2314
  }
8✔
2315

27✔
2316
  /**
27✔
2317
   * Remove a post-set parameters callback.
27✔
2318
   *
27✔
2319
   * @param {PostSetParametersCallback} callback - The callback to remove.
27✔
2320
   * @returns {undefined}
27✔
2321
   */
27✔
2322
  removePostSetParametersCallback(callback) {
27✔
2323
    const idx = this._postSetParametersCallbacks.indexOf(callback);
1✔
2324
    if (idx > -1) {
1✔
2325
      this._postSetParametersCallbacks.splice(idx, 1);
1✔
2326
    }
1✔
2327
  }
1✔
2328

27✔
2329
  /**
27✔
2330
   * Get the fully qualified name of the node.
27✔
2331
   *
27✔
2332
   * @returns {string} - String containing the fully qualified name of the node.
27✔
2333
   */
27✔
2334
  getFullyQualifiedName() {
27✔
2335
    return rclnodejs.getFullyQualifiedName(this.handle);
1✔
2336
  }
1✔
2337

27✔
2338
  /**
27✔
2339
   * Get the RMW implementation identifier
27✔
2340
   * @returns {string} - The RMW implementation identifier.
27✔
2341
   */
27✔
2342
  getRMWImplementationIdentifier() {
27✔
2343
    return rclnodejs.getRMWImplementationIdentifier();
1✔
2344
  }
1✔
2345

27✔
2346
  /**
27✔
2347
   * Return a topic name expanded and remapped.
27✔
2348
   * @param {string} topicName - Topic name to be expanded and remapped.
27✔
2349
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
27✔
2350
   * @returns {string} - A fully qualified topic name.
27✔
2351
   */
27✔
2352
  resolveTopicName(topicName, onlyExpand = false) {
27✔
2353
    if (typeof topicName !== 'string') {
15!
2354
      throw new TypeValidationError('topicName', topicName, 'string', {
×
UNCOV
2355
        nodeName: this.name(),
×
UNCOV
2356
      });
×
UNCOV
2357
    }
×
2358
    return rclnodejs.resolveName(
15✔
2359
      this.handle,
15✔
2360
      topicName,
15✔
2361
      onlyExpand,
15✔
2362
      /*isService=*/ false
15✔
2363
    );
15✔
2364
  }
15✔
2365

27✔
2366
  /**
27✔
2367
   * Return a service name expanded and remapped.
27✔
2368
   * @param {string} service - Service name to be expanded and remapped.
27✔
2369
   * @param {boolean} [onlyExpand=false] - If `true`, remapping rules won't be applied.
27✔
2370
   * @returns {string} - A fully qualified service name.
27✔
2371
   */
27✔
2372
  resolveServiceName(service, onlyExpand = false) {
27✔
2373
    if (typeof service !== 'string') {
7!
2374
      throw new TypeValidationError('service', service, 'string', {
×
UNCOV
2375
        nodeName: this.name(),
×
UNCOV
2376
      });
×
UNCOV
2377
    }
×
2378
    return rclnodejs.resolveName(
7✔
2379
      this.handle,
7✔
2380
      service,
7✔
2381
      onlyExpand,
7✔
2382
      /*isService=*/ true
7✔
2383
    );
7✔
2384
  }
7✔
2385

27✔
2386
  // returns on 1st error or result {successful, reason}
27✔
2387
  _validateParameters(parameters = [], declareParameterMode = false) {
27✔
2388
    for (const parameter of parameters) {
2,574✔
2389
      // detect invalid parameter
2,574✔
2390
      try {
2,574✔
2391
        parameter.validate();
2,574✔
2392
      } catch {
2,574!
2393
        return {
×
UNCOV
2394
          successful: false,
×
UNCOV
2395
          reason: `Invalid ${parameter.name}`,
×
UNCOV
2396
        };
×
UNCOV
2397
      }
×
2398

2,574✔
2399
      // detect undeclared parameter
2,574✔
2400
      if (!this.hasParameterDescriptor(parameter.name)) {
2,574!
2401
        return {
×
UNCOV
2402
          successful: false,
×
UNCOV
2403
          reason: `Parameter ${parameter.name} has not been declared`,
×
UNCOV
2404
        };
×
UNCOV
2405
      }
×
2406

2,574✔
2407
      // detect readonly parameter that can not be updated
2,574✔
2408
      const descriptor = this.getParameterDescriptor(parameter.name);
2,574✔
2409
      if (!declareParameterMode && descriptor.readOnly) {
2,574!
2410
        return {
×
UNCOV
2411
          successful: false,
×
UNCOV
2412
          reason: `Parameter ${parameter.name} is readonly`,
×
UNCOV
2413
        };
×
UNCOV
2414
      }
×
2415

2,574✔
2416
      // validate parameter against descriptor if not an undeclare action
2,574✔
2417
      if (parameter.type != ParameterType.PARAMETER_NOT_SET) {
2,574✔
2418
        try {
2,573✔
2419
          descriptor.validateParameter(parameter);
2,573✔
2420
        } catch {
2,573!
2421
          return {
×
UNCOV
2422
            successful: false,
×
UNCOV
2423
            reason: `Parameter ${parameter.name} does not  readonly`,
×
UNCOV
2424
          };
×
UNCOV
2425
        }
×
2426
      }
2,573✔
2427
    }
2,574✔
2428

2,574✔
2429
    return {
2,574✔
2430
      successful: true,
2,574✔
2431
      reason: null,
2,574✔
2432
    };
2,574✔
2433
  }
2,574✔
2434

27✔
2435
  // Get a Map(nodeName->Parameter[]) of CLI parameter args that
27✔
2436
  // apply to 'this' node, .e.g., -p mynode:foo:=bar -p hello:=world
27✔
2437
  _getNativeParameterOverrides() {
27✔
2438
    const overrides = new Map();
935✔
2439

935✔
2440
    // Get native parameters from rcl context->global_arguments.
935✔
2441
    // rclnodejs returns an array of objects, 1 for each node e.g., -p my_node:foo:=bar,
935✔
2442
    // and a node named '/**' for global parameter rules,
935✔
2443
    // i.e., does not include a node identifier, e.g., -p color:=red
935✔
2444
    // {
935✔
2445
    //   name: string // node name
935✔
2446
    //   parameters[] = {
935✔
2447
    //     name: string
935✔
2448
    //     type: uint
935✔
2449
    //     value: object
935✔
2450
    // }
935✔
2451
    const cliParamOverrideData = rclnodejs.getParameterOverrides(
935✔
2452
      this.context.handle
935✔
2453
    );
935✔
2454

935✔
2455
    // convert native CLI parameterOverrides to Map<nodeName,Array<ParameterOverride>>
935✔
2456
    const cliParamOverrides = new Map();
935✔
2457
    if (cliParamOverrideData) {
935✔
2458
      for (let nodeParamData of cliParamOverrideData) {
8✔
2459
        const nodeName = nodeParamData.name;
12✔
2460
        const nodeParamOverrides = [];
12✔
2461
        for (let paramData of nodeParamData.parameters) {
12✔
2462
          const paramOverride = new Parameter(
17✔
2463
            paramData.name,
17✔
2464
            paramData.type,
17✔
2465
            paramData.value
17✔
2466
          );
17✔
2467
          nodeParamOverrides.push(paramOverride);
17✔
2468
        }
17✔
2469
        cliParamOverrides.set(nodeName, nodeParamOverrides);
12✔
2470
      }
12✔
2471
    }
8✔
2472

935✔
2473
    // collect global CLI global parameters, name == /**
935✔
2474
    let paramOverrides = cliParamOverrides.get('/**'); // array of ParameterOverrides
935✔
2475
    if (paramOverrides) {
935✔
2476
      for (const parameter of paramOverrides) {
5✔
2477
        overrides.set(parameter.name, parameter);
6✔
2478
      }
6✔
2479
    }
5✔
2480

935✔
2481
    // merge CLI node parameterOverrides with global parameterOverrides, replace existing
935✔
2482
    paramOverrides = cliParamOverrides.get(this.name()); // array of ParameterOverrides
935✔
2483
    if (paramOverrides) {
935✔
2484
      for (const parameter of paramOverrides) {
5✔
2485
        overrides.set(parameter.name, parameter);
7✔
2486
      }
7✔
2487
    }
5✔
2488

935✔
2489
    return overrides;
935✔
2490
  }
935✔
2491

27✔
2492
  /**
27✔
2493
   * Invokes the callback with a raw message of the given type. After the callback completes
27✔
2494
   * the message will be destroyed.
27✔
2495
   * @param {function} Type - Message type to create.
27✔
2496
   * @param {function} callback - Callback to invoke. First parameter will be the raw message,
27✔
2497
   * and the second is a function to retrieve the deserialized message.
27✔
2498
   * @returns {undefined}
27✔
2499
   */
27✔
2500
  _runWithMessageType(Type, callback) {
27✔
2501
    let message = new Type();
919✔
2502

919✔
2503
    callback(message.toRawROS(), () => {
919✔
2504
      let result = new Type();
859✔
2505
      result.deserialize(message.refObject);
859✔
2506

859✔
2507
      return result;
859✔
2508
    });
919✔
2509

919✔
2510
    Type.destroyRawROS(message);
919✔
2511
  }
919✔
2512

27✔
2513
  _addActionClient(actionClient) {
27✔
2514
    this._actionClients.push(actionClient);
54✔
2515
    this.syncHandles();
54✔
2516
  }
54✔
2517

27✔
2518
  _addActionServer(actionServer) {
27✔
2519
    this._actionServers.push(actionServer);
53✔
2520
    this.syncHandles();
53✔
2521
  }
53✔
2522

27✔
2523
  _getValidatedTopic(topicName, noDemangle) {
27✔
2524
    if (noDemangle) {
6!
2525
      return topicName;
×
UNCOV
2526
    }
×
2527
    const fqTopicName = rclnodejs.expandTopicName(
6✔
2528
      topicName,
6✔
2529
      this.name(),
6✔
2530
      this.namespace()
6✔
2531
    );
6✔
2532
    validateFullTopicName(fqTopicName);
6✔
2533
    return rclnodejs.remapTopicName(this.handle, fqTopicName);
6✔
2534
  }
6✔
2535

27✔
2536
  _getValidatedServiceName(serviceName, noDemangle) {
27✔
2537
    if (typeof serviceName !== 'string') {
4!
2538
      throw new TypeValidationError('serviceName', serviceName, 'string', {
×
UNCOV
2539
        nodeName: this.name(),
×
UNCOV
2540
      });
×
UNCOV
2541
    }
×
2542

4✔
2543
    if (noDemangle) {
4!
2544
      return serviceName;
×
UNCOV
2545
    }
×
2546

4✔
2547
    const resolvedServiceName = this.resolveServiceName(serviceName);
4✔
2548
    rclnodejs.validateTopicName(resolvedServiceName);
4✔
2549
    return resolvedServiceName;
4✔
2550
  }
4✔
2551
}
27✔
2552

27✔
2553
/**
27✔
2554
 * Create an Options instance initialized with default values.
27✔
2555
 * @returns {Options} - The new initialized instance.
27✔
2556
 * @static
27✔
2557
 * @example
27✔
2558
 * {
27✔
2559
 *   enableTypedArray: true,
27✔
2560
 *   isRaw: false,
27✔
2561
 *   qos: QoS.profileDefault,
27✔
2562
 *   contentFilter: undefined,
27✔
2563
 *   serializationMode: 'default',
27✔
2564
 * }
27✔
2565
 */
27✔
2566
Node.getDefaultOptions = function () {
27✔
2567
  return {
8,604✔
2568
    enableTypedArray: true,
8,604✔
2569
    isRaw: false,
8,604✔
2570
    qos: QoS.profileDefault,
8,604✔
2571
    contentFilter: undefined,
8,604✔
2572
    serializationMode: 'default',
8,604✔
2573
  };
8,604✔
2574
};
27✔
2575

27✔
2576
export default Node;
27✔
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