ros-mobile-bridge 0.1.0

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
@@ -0,0 +1,737 @@
1
+ import { MessageDefinition } from '@foxglove/message-definition';
2
+
3
+ /**
4
+ * Public type contracts for ros-mobile-bridge.
5
+ *
6
+ * Every protocol client (Foxglove WS, rosbridge, future Zenoh) implements
7
+ * IProtocolClient. Consumer code should program against this interface and
8
+ * pick the transport at runtime via ProtocolManager.
9
+ */
10
+ /**
11
+ * A single ROS message delivered to a subscriber callback.
12
+ *
13
+ * `data` is either a decoded JavaScript object or a raw byte array when the
14
+ * protocol could not decode the payload (no schema available, decode failure).
15
+ * The library decodes CDR for Foxglove WS subscriptions when the channel
16
+ * schema is parseable; otherwise it falls back to a `Uint8Array` so the
17
+ * consumer can still inspect the wire bytes.
18
+ */
19
+ interface RosMessage {
20
+ topic: string;
21
+ schemaName: string;
22
+ encoding: 'json' | 'cdr';
23
+ data: Uint8Array | Record<string, unknown>;
24
+ receiveTime: {
25
+ sec: number;
26
+ nsec: number;
27
+ };
28
+ /**
29
+ * Wire payload size in bytes. Populated by the protocol client so consumers
30
+ * don't have to `JSON.stringify` the parsed data to estimate it (which is
31
+ * prohibitively slow for big messages like camera frames).
32
+ */
33
+ byteSize?: number;
34
+ }
35
+ /**
36
+ * Origin of a topic in the ROS graph as observed by the client.
37
+ *
38
+ * - `'robot'`: the topic is advertised by some node in the ROS graph the
39
+ * bridge is attached to (a publisher upstream of the bridge).
40
+ * - `'app'`: the topic was advertised by this client via `publish` or
41
+ * `ensureAdvertised`. Useful when a UI wants to distinguish "things the
42
+ * robot is publishing" from "things this app has published to the bridge".
43
+ */
44
+ type TopicSource = 'robot' | 'app';
45
+ interface TopicInfo {
46
+ topic: string;
47
+ schemaName: string;
48
+ encoding: string;
49
+ source?: TopicSource;
50
+ }
51
+ /**
52
+ * A service advertised by the connected robot.
53
+ *
54
+ * Discovery is best-effort and protocol-specific:
55
+ * - Foxglove WS: the bridge pushes `advertiseServices` on connect and on
56
+ * every ROS-graph change.
57
+ * - rosbridge: the client polls `/rosapi/services` on a slow timer because
58
+ * the bridge has no push notification for service add/remove.
59
+ *
60
+ * `type` is the bare ROS service type (e.g. `std_srvs/srv/Trigger`) when the
61
+ * protocol surfaces it; an empty string otherwise. rosbridge returns empty
62
+ * strings to avoid a multi-roundtrip per-service type lookup.
63
+ */
64
+ interface ServiceInfo {
65
+ name: string;
66
+ type: string;
67
+ }
68
+ /**
69
+ * Options for `IProtocolClient.subscribe`. Used to enforce per-callback rate
70
+ * limiting before message parsing — the dominant JS-thread cost for high-
71
+ * bandwidth topics like compressed camera frames.
72
+ */
73
+ interface SubscribeOptions {
74
+ /**
75
+ * Maximum delivery rate in Hz. Messages within the throttle window are
76
+ * dropped before `JSON.parse` / CDR decode, so a noisy publisher cannot
77
+ * starve the JS thread. `undefined` means deliver every message.
78
+ */
79
+ maxFrequency?: number;
80
+ /**
81
+ * Opt out of the bandwidth-aware adaptive throttle. By default, when a
82
+ * subscription's sustained bytes/sec crosses an internal threshold the
83
+ * client tightens its effective delivery rate beyond what `maxFrequency`
84
+ * requested, to keep the JS thread responsive for gesture and control
85
+ * work. Set `true` when the device has been sized for the workload and
86
+ * the caller wants raw rate.
87
+ */
88
+ disableAdaptive?: boolean;
89
+ }
90
+ /**
91
+ * State of the per-subscription circuit breaker.
92
+ *
93
+ * The breaker trips when even the deepest adaptive-throttle bucket can't keep
94
+ * JS-thread lag below a "still saturated" threshold for a sustained period —
95
+ * the workload is fundamentally too heavy for the transport on the current
96
+ * device. While tripped the subscription is unsubscribed at the bridge,
97
+ * freeing the JS thread, network, and memory entirely.
98
+ *
99
+ * - `closed`: normal operation; throttle handles everything.
100
+ * - `tripped_auto`: subscription paused; auto-retry timer running. Cooldown
101
+ * is exponential (30 s, 60 s, 120 s, 300 s on repeated trips within a
102
+ * single connection).
103
+ * - `tripped_manual`: subscription paused with no auto-retry. The user
104
+ * opted out via UI to stop the periodic stutter from failing recovery
105
+ * attempts.
106
+ * - `half_open`: subscription resumed; the breaker watches lag for ~10 s.
107
+ * If lag stays low the breaker closes; if it spikes again it re-trips
108
+ * with a longer cooldown.
109
+ */
110
+ type CircuitBreakerState = 'closed' | 'tripped_auto' | 'tripped_manual' | 'half_open';
111
+ /**
112
+ * Snapshot of the adaptive-throttle state for one subscription. Surfaced so
113
+ * consumers can show users when delivery is being capped below what they
114
+ * requested (e.g. a "5 Hz" / "1 Hz" / "0.5 Hz" badge near a widget).
115
+ * `adaptiveMinIntervalMs > 0` means the throttle is actively limiting.
116
+ */
117
+ interface SubscriptionStats {
118
+ /** Effective adaptive cap interval in ms. `0` means no cap. */
119
+ adaptiveMinIntervalMs: number;
120
+ /**
121
+ * Human-readable label for the active bucket: `"none"`, `"10 Hz"`,
122
+ * `"5 Hz"`, `"1 Hz"`, `"0.5 Hz"`. Renderable verbatim.
123
+ */
124
+ bucketLabel: string;
125
+ /**
126
+ * Last computed bytes/sec for this subscription over a rolling 1 s window.
127
+ * Useful for diagnostics overlays.
128
+ */
129
+ bytesPerSec: number;
130
+ }
131
+ /**
132
+ * Options for `IProtocolClient.publish`.
133
+ */
134
+ interface PublishOptions {
135
+ /**
136
+ * Priority hint.
137
+ *
138
+ * - `'control'`: gesture, E-Stop, action cancel, and other safety-critical
139
+ * publishes that must not be starved by incoming-message parse work.
140
+ * The client routes control publishes through a small outbox flushed at
141
+ * the top of every incoming WebSocket message handler, so they ride out
142
+ * before the JS thread is consumed by the next parse macrotask.
143
+ * - `'data'` (default): sent directly via synchronous `ws.send`. Most
144
+ * publishes don't share a tick with parse work and don't benefit from
145
+ * the outbox indirection.
146
+ *
147
+ * The library targets ROS 2 explicitly; the names reflect the semantics
148
+ * (Twist on `/cmd_vel`, action cancel goals, E-Stop publishes) rather
149
+ * than a generic high/normal pair.
150
+ */
151
+ priority?: 'control' | 'data';
152
+ }
153
+ type ConnectionStatus = 'disconnected' | 'connecting' | 'connected' | 'error';
154
+ type ProtocolType = 'foxglove-ws' | 'rosbridge' | 'zenoh';
155
+ /**
156
+ * Connection parameters consumed by `ProtocolManager.connect`. Only the
157
+ * fields the library needs to open a WebSocket are declared here; identifiers,
158
+ * display names, and any "saved profile" concept are the host application's
159
+ * concern and should live in its own store.
160
+ */
161
+ interface ConnectionOptions {
162
+ protocol: ProtocolType;
163
+ host: string;
164
+ /**
165
+ * Port to connect to. Optional; defaults to `DEFAULT_PORTS[protocol]`
166
+ * (8765 for `foxglove-ws`, 9090 for `rosbridge`, 7447 for `zenoh`).
167
+ */
168
+ port?: number;
169
+ /**
170
+ * Use the secure `wss://` scheme. Optional; defaults to `false` (`ws://`).
171
+ */
172
+ secure?: boolean;
173
+ }
174
+ /**
175
+ * User-selectable adaptive-throttle mode. Each mode maps to a curve of
176
+ * lag-to-delivery-rate buckets; the curves can be overridden per-host via
177
+ * `ProtocolClientOptions.presetOverrides`.
178
+ *
179
+ * - `'performance'`: no adaptive cap, deliver every message the user's
180
+ * `maxFrequency` allows.
181
+ * - `'auto'` (default): moderate curve tuned for general-purpose mobile use.
182
+ * - `'efficient'`: aggressive curve that prioritises gesture authority over
183
+ * throughput on lower-end devices.
184
+ *
185
+ * @experimental The throttle-tuning surface (this type, `BucketDef`, and
186
+ * `ProtocolClientOptions.presetOverrides`) is part of the public API but may
187
+ * evolve before `1.0`. The mode names themselves are stable.
188
+ */
189
+ type ThrottleMode = 'performance' | 'auto' | 'efficient';
190
+ /**
191
+ * One step in an adaptive-throttle curve. A curve is an array of buckets in
192
+ * ascending `threshold` order; the highest-threshold bucket whose value the
193
+ * measured JS-thread lag exceeds wins, and its `minIntervalMs` becomes the
194
+ * effective delivery interval for every subscription on that throttle mode.
195
+ *
196
+ * The first bucket in every curve must have `threshold === 0` — that's the
197
+ * "no throttle" base case the throttle falls through to when lag is below
198
+ * every higher threshold. Validation in `presetOverrides` enforces this.
199
+ *
200
+ * @experimental Part of the public throttle-tuning surface; the shape is
201
+ * semver-stable but may gain optional fields before `1.0`.
202
+ */
203
+ interface BucketDef {
204
+ /**
205
+ * Minimum JS-thread lag (ms) at which this bucket activates. Compared
206
+ * against the rolling-window max from `getMaxLagMs()`.
207
+ */
208
+ threshold: number;
209
+ /**
210
+ * Minimum interval (ms) between deliveries when this bucket is active.
211
+ * `0` means "no cap" (deliver every message).
212
+ */
213
+ minIntervalMs: number;
214
+ /**
215
+ * Human-readable label used by diagnostics (`bucketLabelForLag`,
216
+ * `getSubscriptionStats.bucketLabel`). Convention: `'none'` for the
217
+ * no-cap bucket, frequency strings like `'5 Hz'` for capped buckets.
218
+ */
219
+ label: string;
220
+ }
221
+ /**
222
+ * Optional callbacks injected by the host application. These let the
223
+ * protocol layer stay decoupled from app-specific concerns (metrics
224
+ * pipelines, logging frameworks, performance-mode settings).
225
+ *
226
+ * Every callback is optional. The library has sensible no-op defaults.
227
+ */
228
+ interface ProtocolClientOptions {
229
+ /**
230
+ * Called with round-trip latency in milliseconds after each successful
231
+ * keep-alive ping/pong or latency probe.
232
+ */
233
+ onLatency?: (rttMs: number) => void;
234
+ /**
235
+ * Logger interface. Falls back to silent no-ops if not provided. The
236
+ * library never writes to `console` directly when a logger is supplied.
237
+ */
238
+ logger?: ProtocolLogger;
239
+ /**
240
+ * Returns the user-selected throttle mode. Read on every incoming message
241
+ * so a Settings change applies immediately to existing subscriptions
242
+ * without resubscribing. Defaults to `'auto'` when not provided.
243
+ */
244
+ getThrottleMode?: () => ThrottleMode;
245
+ /**
246
+ * Override the built-in throttle curves on a per-mode basis. Modes not
247
+ * present in this map (or modes whose override fails validation) fall
248
+ * back to the library's tuned defaults.
249
+ *
250
+ * The library was tuned on one device class; consumers shipping to a
251
+ * different device profile (slower CPU, larger screen, etc.) can supply
252
+ * their own curves here without forking the library.
253
+ *
254
+ * Validation runs once at construction time. A rejected override produces
255
+ * a `logger.warn` and falls back to the default for that mode only; other
256
+ * modes' overrides still take effect. The rules enforced:
257
+ *
258
+ * - The bucket array is non-empty.
259
+ * - The first bucket has `threshold === 0` (the "no throttle" base case).
260
+ *
261
+ * The library does not enforce that thresholds are sorted ascending or
262
+ * that labels are unique within an array — those are consumer-quality
263
+ * concerns; the throttle still terminates with sensible-enough results
264
+ * if they're violated.
265
+ *
266
+ * Note: `bucketLabelForLag(mode, lagMs)` is a stateless module-level
267
+ * diagnostic and always reads the library defaults, never per-client
268
+ * overrides. If a consumer needs override-aware bucket labelling, derive
269
+ * it from `getSubscriptionStats(topic).bucketLabel` instead.
270
+ *
271
+ * @experimental Part of the public throttle-tuning surface; the override
272
+ * shape is semver-stable but may evolve before `1.0`.
273
+ */
274
+ presetOverrides?: Partial<Record<ThrottleMode, BucketDef[]>>;
275
+ }
276
+ interface ProtocolLogger {
277
+ log: (...args: unknown[]) => void;
278
+ warn: (...args: unknown[]) => void;
279
+ error: (...args: unknown[]) => void;
280
+ }
281
+ /**
282
+ * The contract every transport implements. Program against this interface
283
+ * and use `ProtocolManager` to pick the concrete implementation at runtime.
284
+ */
285
+ interface IProtocolClient {
286
+ connect(url: string): Promise<void>;
287
+ disconnect(): Promise<void>;
288
+ readonly isConnected: boolean;
289
+ getAvailableTopics(): Promise<TopicInfo[]>;
290
+ /**
291
+ * Subscribe to a topic. Returns an unsubscribe function.
292
+ *
293
+ * If `options.maxFrequency` is set, the client drops messages without
294
+ * parsing them when they arrive sooner than `1000 / maxFrequency` ms
295
+ * after the previous delivery to this callback. Throttle state is
296
+ * per-callback, so multiple subscribers to the same topic with different
297
+ * rates are isolated.
298
+ */
299
+ subscribe(topic: string, onMessage: (msg: RosMessage) => void, options?: SubscribeOptions): () => void;
300
+ publish(topic: string, schemaName: string, data: Record<string, unknown>, options?: PublishOptions): void;
301
+ /**
302
+ * Declare intent to publish on `topic` ahead of the first data message,
303
+ * so a subsequent `publish` to that topic sends synchronously instead of
304
+ * paying the advertise-then-setTimeout delay. Safety-critical paths
305
+ * (E-Stop, action cancel goals on AppState background) need the first
306
+ * publish on a rarely-used channel to land before the socket tears down.
307
+ * No-op if already advertised.
308
+ */
309
+ ensureAdvertised(topic: string, schemaName: string): void;
310
+ /**
311
+ * Unadvertise a topic the client previously published to. Tells the
312
+ * bridge to tear down its ROS publisher.
313
+ */
314
+ unadvertise(topic: string): void;
315
+ /**
316
+ * Publish a zero-velocity `geometry_msgs/msg/Twist` on `/cmd_vel`. Used by
317
+ * dead-man's-switch paths (app background, disconnect, E-Stop) to halt
318
+ * robot motion. No-op if the client has never published a Twist on this
319
+ * connection.
320
+ */
321
+ publishZeroTwist(): void;
322
+ /**
323
+ * Current breaker state for `topic`. Returns `'closed'` when no
324
+ * subscription exists, so consumers don't need to null-check.
325
+ */
326
+ getBreakerState(topic: string): CircuitBreakerState;
327
+ /**
328
+ * `Date.now()` when the next auto-retry will fire for `topic`, or `null`
329
+ * when the breaker is not in `tripped_auto`. Used by UIs to render a
330
+ * countdown.
331
+ */
332
+ getBreakerNextRetryAt(topic: string): number | null;
333
+ /**
334
+ * Snapshot of the adaptive-throttle state for `topic`, or `null` when no
335
+ * subscription exists. Used to render "currently capped at X Hz" badges.
336
+ */
337
+ getSubscriptionStats(topic: string): SubscriptionStats | null;
338
+ /**
339
+ * Manual retry from any tripped state. Resumes the subscription via
340
+ * `half_open`. No-op if the breaker is already closed or no subscription
341
+ * exists.
342
+ */
343
+ breakerRetry(topic: string): void;
344
+ /**
345
+ * Cancel auto-retry for a subscription whose breaker is in `tripped_auto`,
346
+ * transitioning to `tripped_manual`. No-op otherwise.
347
+ */
348
+ breakerDisable(topic: string): void;
349
+ /**
350
+ * Subscribe to breaker-state-change notifications for a topic. The
351
+ * callback fires on every transition. Returns an unsubscribe function.
352
+ */
353
+ onBreakerStateChange(topic: string, cb: (state: CircuitBreakerState) => void): () => void;
354
+ callService(service: string, request: Record<string, unknown>): Promise<Record<string, unknown>>;
355
+ /**
356
+ * Snapshot of services currently advertised by the robot. Returns an
357
+ * empty list when discovery has not completed (e.g. immediately after
358
+ * connect on rosbridge, before the first `/rosapi/services` poll).
359
+ */
360
+ getAvailableServices(): ServiceInfo[];
361
+ /**
362
+ * Subscribe to service-list changes. Fires immediately with the current
363
+ * list and again on every update. Returns an unsubscribe function.
364
+ */
365
+ onServicesChange(cb: (services: ServiceInfo[]) => void): () => void;
366
+ /**
367
+ * Returns a default JSON template for a message schema, with every field
368
+ * set to its zero / empty default. Returns `null` if the schema is
369
+ * unknown or the protocol does not carry it (rosbridge does not embed
370
+ * schemas in its wire format; Foxglove WS does).
371
+ */
372
+ getSchemaTemplate(schemaName: string): Record<string, unknown> | null;
373
+ /** Current reconnection attempt. `0` when not reconnecting. */
374
+ readonly reconnectAttempt: number;
375
+ /** Maximum reconnect attempts before the client gives up. */
376
+ readonly maxReconnectAttempts: number;
377
+ onStatusChange(cb: (status: ConnectionStatus) => void): () => void;
378
+ onTopicsChange(cb: (topics: TopicInfo[]) => void): () => void;
379
+ onLog(cb: (log: string) => void): () => void;
380
+ }
381
+
382
+ declare class FoxgloveClient implements IProtocolClient {
383
+ private readonly onLatency;
384
+ private readonly logger;
385
+ private readonly getThrottleMode;
386
+ private readonly presets;
387
+ private ws;
388
+ private url;
389
+ private status;
390
+ private statusListeners;
391
+ private logListeners;
392
+ private topicsListeners;
393
+ private servicesListeners;
394
+ constructor(options?: ProtocolClientOptions);
395
+ private channels;
396
+ private topicToChannelId;
397
+ private nextSubscriptionId;
398
+ private subscriptions;
399
+ private topicToSubscriptionId;
400
+ private breakerListeners;
401
+ private messageReaders;
402
+ private nextClientChannelId;
403
+ private advertisedTopics;
404
+ private hasPublishedTwist;
405
+ private static readonly CONTROL_FLUSH_BATCH;
406
+ private controlOutbox;
407
+ private controlFlushScheduled;
408
+ private nextServiceCallId;
409
+ private pendingServiceCalls;
410
+ private availableServices;
411
+ private pingTimer;
412
+ private pongTimer;
413
+ private lastPingSentTime;
414
+ private reconnectAttempts;
415
+ private reconnectTimer;
416
+ private connectionTimeoutTimer;
417
+ private intentionalDisconnect;
418
+ private connectResolve;
419
+ private connectReject;
420
+ private serverInfoReceived;
421
+ get isConnected(): boolean;
422
+ get reconnectAttempt(): number;
423
+ get maxReconnectAttempts(): number;
424
+ connect(url: string): Promise<void>;
425
+ disconnect(): Promise<void>;
426
+ getAvailableTopics(): Promise<TopicInfo[]>;
427
+ getSchemaTemplate(schemaName: string): Record<string, unknown> | null;
428
+ subscribe(topic: string, onMessage: (msg: RosMessage) => void, options?: SubscribeOptions): () => void;
429
+ publish(topic: string, schemaName: string, data: Record<string, unknown>, options?: PublishOptions): void;
430
+ private scheduleControlFlush;
431
+ private flushControlOutbox;
432
+ ensureAdvertised(topic: string, schemaName: string): void;
433
+ unadvertise(topic: string): void;
434
+ private sendBinaryMessage;
435
+ callService(service: string, request: Record<string, unknown>): Promise<Record<string, unknown>>;
436
+ onStatusChange(cb: (status: ConnectionStatus) => void): () => void;
437
+ onTopicsChange(cb: (topics: TopicInfo[]) => void): () => void;
438
+ getAvailableServices(): ServiceInfo[];
439
+ onServicesChange(cb: (services: ServiceInfo[]) => void): () => void;
440
+ onLog(cb: (log: string) => void): () => void;
441
+ publishZeroTwist(): void;
442
+ private performConnect;
443
+ private handleWsMessage;
444
+ private handleJsonMessage;
445
+ private handleBinaryMessage;
446
+ private handleServerInfo;
447
+ private handleAdvertise;
448
+ private handleUnadvertise;
449
+ private handleAdvertiseServices;
450
+ private notifyServicesChanged;
451
+ private handleServiceCallResponse;
452
+ private startPingLoop;
453
+ private stopPingLoop;
454
+ private handlePong;
455
+ private handleConnectionError;
456
+ private handleClose;
457
+ private scheduleReconnect;
458
+ private unsubscribeTopic;
459
+ getBreakerState(topic: string): CircuitBreakerState;
460
+ getBreakerNextRetryAt(topic: string): number | null;
461
+ getSubscriptionStats(topic: string): {
462
+ adaptiveMinIntervalMs: number;
463
+ bucketLabel: string;
464
+ bytesPerSec: number;
465
+ } | null;
466
+ breakerRetry(topic: string): void;
467
+ breakerDisable(topic: string): void;
468
+ onBreakerStateChange(topic: string, cb: (state: CircuitBreakerState) => void): () => void;
469
+ private safePublishZeroTwist;
470
+ private cleanup;
471
+ private clearConnectionTimeout;
472
+ private setStatus;
473
+ private sendJson;
474
+ private notifyTopicsChanged;
475
+ private log;
476
+ }
477
+
478
+ /**
479
+ * RosbridgeClient — rosbridge v2 protocol implementation.
480
+ *
481
+ * Implements the rosbridge v2 JSON protocol directly over the runtime's
482
+ * `WebSocket`. No `roslib` dependency: that library pulls in Node-only
483
+ * modules (`bson`, `ws`) that break in React Native and that we don't need
484
+ * because the protocol is a small JSON envelope.
485
+ *
486
+ * Protocol spec: https://github.com/RobotWebTools/rosbridge_suite/blob/ros2/ROSBRIDGE_PROTOCOL.md
487
+ * Default port: 9090.
488
+ *
489
+ * Features:
490
+ *
491
+ * - Topic discovery via the `/rosapi/topics` service.
492
+ * - Subscribe with `throttle_rate` and `queue_length=1` (drop old, keep
493
+ * latest) for sane defaults on high-rate topics.
494
+ * - Publish with auto-advertise on first send.
495
+ * - Service calls with a 30 s timeout.
496
+ * - Dead-man's switch: zero Twist on unexpected disconnect.
497
+ * - Exponential backoff reconnection (1 s → 2 s → 4 s → 8 s → 16 s, max 5
498
+ * attempts).
499
+ * - `tryDropPublishBeforeParse` fast-path: bounded substring scan extracts
500
+ * `op` and `topic` from a `publish` envelope so we can drop messages no
501
+ * callback wants without paying `JSON.parse` cost on the full payload.
502
+ * Matters for high-bandwidth topics where parse dominates per-message
503
+ * work.
504
+ */
505
+
506
+ declare class RosbridgeClient implements IProtocolClient {
507
+ private readonly onLatency;
508
+ private readonly logger;
509
+ private readonly getThrottleMode;
510
+ private readonly presets;
511
+ private ws;
512
+ private url;
513
+ private status;
514
+ private statusListeners;
515
+ private logListeners;
516
+ private topicsListeners;
517
+ private servicesListeners;
518
+ private availableServices;
519
+ private servicesPollTimer;
520
+ constructor(options?: ProtocolClientOptions);
521
+ private activeSubscriptions;
522
+ private breakerListeners;
523
+ private advertisedTopics;
524
+ private hasPublishedTwist;
525
+ private static readonly CONTROL_FLUSH_BATCH;
526
+ private controlOutbox;
527
+ private controlFlushScheduled;
528
+ private discoveredTopics;
529
+ private pendingServiceCalls;
530
+ private serviceCallCounter;
531
+ private latencyProbeTimer;
532
+ private reconnectAttempts;
533
+ private reconnectTimer;
534
+ private connectionTimeoutTimer;
535
+ private intentionalDisconnect;
536
+ get isConnected(): boolean;
537
+ get reconnectAttempt(): number;
538
+ get maxReconnectAttempts(): number;
539
+ connect(url: string): Promise<void>;
540
+ disconnect(): Promise<void>;
541
+ getAvailableTopics(): Promise<TopicInfo[]>;
542
+ getSchemaTemplate(_schemaName: string): Record<string, unknown> | null;
543
+ subscribe(topic: string, onMessage: (msg: RosMessage) => void, options?: SubscribeOptions): () => void;
544
+ publish(topic: string, schemaName: string, data: Record<string, unknown>, options?: PublishOptions): void;
545
+ private scheduleControlFlush;
546
+ private flushControlOutbox;
547
+ ensureAdvertised(topic: string, schemaName: string): void;
548
+ unadvertise(topic: string): void;
549
+ callService(service: string, request: Record<string, unknown>): Promise<Record<string, unknown>>;
550
+ onStatusChange(cb: (status: ConnectionStatus) => void): () => void;
551
+ onTopicsChange(cb: (topics: TopicInfo[]) => void): () => void;
552
+ getAvailableServices(): ServiceInfo[];
553
+ onServicesChange(cb: (services: ServiceInfo[]) => void): () => void;
554
+ private discoverServices;
555
+ private startServicesPoll;
556
+ private stopServicesPoll;
557
+ private notifyServicesChanged;
558
+ onLog(cb: (log: string) => void): () => void;
559
+ publishZeroTwist(): void;
560
+ private performConnect;
561
+ private handleMessage;
562
+ /**
563
+ * Drop a publish message before paying full `JSON.parse` cost.
564
+ *
565
+ * Rosbridge frames look like `{"op":"publish","topic":"…","msg":{…}}`.
566
+ * For fat payloads (base64-encoded camera frames, large arrays)
567
+ * `JSON.parse` on the whole envelope dominates per-message cost. We do a
568
+ * cheap substring search to extract `op` and `topic`, run the same
569
+ * throttle/breaker accounting `handlePublish` would do, and return `true`
570
+ * to skip the parse when no callback wants the message right now.
571
+ *
572
+ * Handles both compact (`{"op":"publish"`) and pretty (`{"op": "publish"`)
573
+ * JSON forms.
574
+ */
575
+ private tryDropPublishBeforeParse;
576
+ private handlePublish;
577
+ private handleServiceResponse;
578
+ private unsubscribeTopic;
579
+ getBreakerState(topic: string): CircuitBreakerState;
580
+ getBreakerNextRetryAt(topic: string): number | null;
581
+ getSubscriptionStats(topic: string): {
582
+ adaptiveMinIntervalMs: number;
583
+ bucketLabel: string;
584
+ bytesPerSec: number;
585
+ } | null;
586
+ breakerRetry(topic: string): void;
587
+ breakerDisable(topic: string): void;
588
+ onBreakerStateChange(topic: string, cb: (state: CircuitBreakerState) => void): () => void;
589
+ private safePublishZeroTwist;
590
+ private startLatencyProbe;
591
+ private stopLatencyProbe;
592
+ private scheduleReconnect;
593
+ private cleanupConnection;
594
+ private cleanup;
595
+ private clearConnectionTimeout;
596
+ private send;
597
+ private setStatus;
598
+ private notifyTopicsChanged;
599
+ private log;
600
+ }
601
+
602
+ declare class ProtocolManager {
603
+ private activeClient;
604
+ private activeOptions;
605
+ private clientOptions;
606
+ /**
607
+ * Set options forwarded to every client constructed by this manager.
608
+ * Host applications typically call this once at startup.
609
+ */
610
+ setClientOptions(options: ProtocolClientOptions): void;
611
+ /**
612
+ * Create and connect a protocol client for the given options.
613
+ *
614
+ * For `protocol: 'zenoh'`, throws a clear "planned for v0.2.0" error —
615
+ * the v0.1.0 release does not ship a Zenoh implementation.
616
+ */
617
+ connect(options: ConnectionOptions): Promise<IProtocolClient>;
618
+ /**
619
+ * Disconnect the active client and forget it.
620
+ */
621
+ disconnect(): Promise<void>;
622
+ /**
623
+ * Currently active client, or `null` if not connected.
624
+ */
625
+ getClient(): IProtocolClient | null;
626
+ /**
627
+ * Currently active connection options, or `null` if not connected.
628
+ */
629
+ getOptions(): ConnectionOptions | null;
630
+ private createClient;
631
+ }
632
+
633
+ /**
634
+ * schemaToTemplate — derive a default JSON payload from a parsed ROS message
635
+ * definition.
636
+ *
637
+ * Takes the array returned by `@foxglove/rosmsg` (for `.msg` and ros2msg) or
638
+ * `@foxglove/ros2idl-parser` (for ros2idl). The first element is the root
639
+ * message; subsequent elements are referenced types. Returns a plain object
640
+ * with every field set to its zero / empty default, ready to use as a
641
+ * starting point for a publish payload editor.
642
+ */
643
+
644
+ /**
645
+ * Build a default JSON template from a parsed message definition. Used by
646
+ * `IProtocolClient.getSchemaTemplate` to surface ready-to-edit payloads for
647
+ * publish UIs.
648
+ */
649
+ declare function schemaToTemplate(definitions: MessageDefinition[]): Record<string, unknown>;
650
+
651
+ /**
652
+ * jsonSchemaToTemplate — derive a zero-valued JSON payload from a JSON Schema.
653
+ *
654
+ * Used by the Foxglove WebSocket path to turn bridges that ship JSON Schema
655
+ * into Topic-Publisher / field-path templates. The reference foxglove_bridge
656
+ * ships ros2idl instead, which `schemaToTemplate` handles; this parser
657
+ * covers the remaining gap so consumers don't need a hard-coded table of
658
+ * well-known ROS 2 types.
659
+ *
660
+ * Scope: draft-07-compatible JSON Schema, restricted to the subset a bridge
661
+ * typically emits for ROS message shapes (object / array / primitive).
662
+ * Does not resolve `$ref`, `allOf` / `oneOf` / `anyOf`, or enum defaults.
663
+ */
664
+ declare function jsonSchemaToTemplate(schema: unknown): unknown;
665
+
666
+ /**
667
+ * Default TCP port for each supported protocol. Useful for consumers
668
+ * building connection-configuration UIs that want a sensible starting
669
+ * value when the user changes protocol.
670
+ */
671
+ declare const DEFAULT_PORTS: Record<ProtocolType, number>;
672
+
673
+ /**
674
+ * Library-tuned throttle curves. Override via
675
+ * `ProtocolClientOptions.presetOverrides` to ship a per-device-class curve.
676
+ * Exported for use by consumers building their own preset variants on top
677
+ * of the defaults (e.g. `{ ...DEFAULT_PRESETS, auto: [...customAuto] }`).
678
+ *
679
+ * @experimental The override *shape* (`BucketDef`, `ThrottleMode`,
680
+ * `presetOverrides`) is semver-stable, but the default *values* in this map
681
+ * may be rebalanced in any patch release as device-tuning data accrues. Do
682
+ * not snapshot these numbers and assume they're frozen; reference the export
683
+ * if you want to track the current defaults.
684
+ */
685
+ declare const DEFAULT_PRESETS: Record<ThrottleMode, BucketDef[]>;
686
+ /**
687
+ * Resolve which bucket a given lag value would land in for the active mode
688
+ * under the library's **default** presets. Independent of any tracker —
689
+ * pass a raw lag measurement (typically from `getMaxLagMs()`) and the
690
+ * active throttle mode, and get back the bucket label the default-tuned
691
+ * throttle would apply at that lag.
692
+ *
693
+ * Useful for diagnostics overlays that want to show "JS lag is N ms →
694
+ * bucket X" so observers can correlate measured lag with the throttle
695
+ * policy.
696
+ *
697
+ * **Note on `presetOverrides`:** this function is a stateless module-level
698
+ * helper and has no awareness of per-client overrides. If a consumer
699
+ * supplies `presetOverrides.auto`, calling `bucketLabelForLag('auto', lag)`
700
+ * still returns the **default** bucket label for that lag value, not the
701
+ * override's. For override-aware bucket labels, read
702
+ * `getSubscriptionStats(topic).bucketLabel` off a live subscription.
703
+ */
704
+ declare function bucketLabelForLag(mode: ThrottleMode, lagMs: number): string;
705
+
706
+ /**
707
+ * Max observed JS-thread lag (ms) over the last `WINDOW_MS`. Auto-starts
708
+ * the monitor on first call. Returns `0` if no samples have been collected
709
+ * yet.
710
+ */
711
+ declare function getMaxLagMs(): number;
712
+ /**
713
+ * Percentile statistics over the long-term history buffer (roughly the last
714
+ * 2 minutes). Returns `null` when no samples have been collected yet.
715
+ */
716
+ declare function getLagStats(): {
717
+ count: number;
718
+ durationSec: number;
719
+ p50: number;
720
+ p90: number;
721
+ p99: number;
722
+ max: number;
723
+ } | null;
724
+ /**
725
+ * CSV dump of the history buffer. One row per sample, mode-tagged so a
726
+ * recording that spans a throttle-mode change still tells you which lag
727
+ * values belong to which mode. Useful for attaching to bug reports.
728
+ */
729
+ declare function getLagHistoryCsv(): string;
730
+ /**
731
+ * Clear the long-term history buffer. The rolling 1 s window used by the
732
+ * throttle keeps running, so live throttle decisions stay correct. Useful
733
+ * when starting a new test session.
734
+ */
735
+ declare function clearLagHistory(): void;
736
+
737
+ export { type BucketDef, type CircuitBreakerState, type ConnectionOptions, type ConnectionStatus, DEFAULT_PORTS, DEFAULT_PRESETS, FoxgloveClient, type IProtocolClient, type ProtocolClientOptions, type ProtocolLogger, ProtocolManager, type ProtocolType, type PublishOptions, type RosMessage, RosbridgeClient, type ServiceInfo, type SubscribeOptions, type SubscriptionStats, type ThrottleMode, type TopicInfo, type TopicSource, bucketLabelForLag, clearLagHistory, getLagHistoryCsv, getLagStats, getMaxLagMs, jsonSchemaToTemplate, schemaToTemplate };