├── nodejs.d.ts ├── nodejs.js ├── examples ├── ros1-chatter │ ├── .eslintrc.yaml │ ├── tsconfig.json │ ├── package.json │ ├── src │ │ └── index.ts │ └── yarn.lock └── ros1-turtlesim-test │ ├── .eslintrc.yaml │ ├── README.md │ ├── sample-robot-docker │ ├── build-robot.sh │ ├── entrypoint.sh │ ├── start-robot.sh │ └── Dockerfile │ ├── tsconfig.json │ ├── package.json │ ├── src │ └── index.ts │ └── yarn.lock ├── .prettierrc.yaml ├── jest.config.json ├── src ├── nodejs │ ├── index.ts │ ├── roscore.ts │ ├── platform.ts │ ├── TcpServerNode.ts │ └── TcpSocketNode.ts ├── XmlRpcTypes.ts ├── LoggerService.ts ├── difference.ts ├── SubscriberLink.ts ├── index.ts ├── Publisher.ts ├── Client.ts ├── objectTests.ts ├── concatData.ts ├── concatData.test.ts ├── backoff.test.ts ├── PublisherLink.ts ├── Connection.ts ├── mock │ ├── MockHttpServer.ts │ ├── MockTcp.ts │ └── MockXmlRpc.ts ├── backoff.ts ├── RosMaster.test.ts ├── RosXmlRpcClient.ts ├── objectTests.test.ts ├── RosFollowerClient.ts ├── TcpTypes.ts ├── RosParamClient.ts ├── RosTcpMessageStream.ts ├── RosMasterClient.ts ├── RosTcpMessageStream.test.ts ├── RosNode.test.ts ├── TcpConnection.test.ts ├── RosMasterClient.test.ts ├── Publication.ts ├── Subscription.ts ├── TcpPublisher.ts ├── RosFollower.ts ├── TcpClient.ts ├── TcpConnection.ts ├── RosMaster.ts └── RosNode.ts ├── tsconfig.dts.json ├── .eslintrc.yaml ├── .vscode ├── settings.json └── extensions.json ├── .github └── workflows │ └── ci.yml ├── tsconfig.json ├── LICENSE ├── .gitignore ├── package.json └── README.md /nodejs.d.ts: -------------------------------------------------------------------------------- 1 | export * from "./dist/nodejs/index.js"; 2 | -------------------------------------------------------------------------------- /nodejs.js: -------------------------------------------------------------------------------- 1 | module.exports = require("./dist/nodejs/index.js"); 2 | -------------------------------------------------------------------------------- /examples/ros1-chatter/.eslintrc.yaml: -------------------------------------------------------------------------------- 1 | parserOptions: 2 | project: examples/ros1-chatter/tsconfig.json 3 | -------------------------------------------------------------------------------- /.prettierrc.yaml: -------------------------------------------------------------------------------- 1 | arrowParens: always 2 | printWidth: 100 3 | trailingComma: "all" 4 | tabWidth: 2 5 | semi: true 6 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/.eslintrc.yaml: -------------------------------------------------------------------------------- 1 | parserOptions: 2 | project: examples/ros1-turtlesim-test/tsconfig.json 3 | -------------------------------------------------------------------------------- /jest.config.json: -------------------------------------------------------------------------------- 1 | { 2 | "testMatch": ["/src/**/*.test.ts"], 3 | "transform": { 4 | "^.+\\.ts$": "ts-jest" 5 | } 6 | } 7 | -------------------------------------------------------------------------------- /src/nodejs/index.ts: -------------------------------------------------------------------------------- 1 | // Node.js backend 2 | export * from "./platform"; 3 | export * from "./TcpServerNode"; 4 | export * from "./TcpSocketNode"; 5 | -------------------------------------------------------------------------------- /tsconfig.dts.json: -------------------------------------------------------------------------------- 1 | { 2 | "extends": "./tsconfig.json", 3 | "include": ["./*.d.ts"], 4 | "compilerOptions": { 5 | "noEmit": true 6 | } 7 | } 8 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/README.md: -------------------------------------------------------------------------------- 1 | # ros1-turtlesim-test 2 | 3 | An example application connecting to a ROS1 robot using the `@foxglove/ros1` library. 4 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/sample-robot-docker/build-robot.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | 3 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )" 4 | cd $DIR 5 | 6 | docker build --tag sample-robot . 7 | -------------------------------------------------------------------------------- /src/XmlRpcTypes.ts: -------------------------------------------------------------------------------- 1 | import { XmlRpcFault, XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | export type RosXmlRpcResponse = [code: number, msg: string, value: XmlRpcValue]; 4 | export type RosXmlRpcResponseOrFault = RosXmlRpcResponse | XmlRpcFault; 5 | -------------------------------------------------------------------------------- /src/LoggerService.ts: -------------------------------------------------------------------------------- 1 | export interface LoggerService { 2 | warn?(message: string, context?: string): void; 3 | info?(message: string, context?: string): void; 4 | debug?(message: string, context?: string): void; 5 | verbose?(message: string, context?: string): void; 6 | } 7 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/sample-robot-docker/entrypoint.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | 3 | mkdir -p ~/catkin_ws/src 4 | cd ~/catkin_ws/ 5 | source /opt/ros/noetic/setup.bash 6 | catkin_make 7 | source ~/catkin_ws/devel/setup.bash 8 | 9 | roscore & 10 | 11 | xvfb-run --auto-servernum rosrun turtlesim turtlesim_node 12 | -------------------------------------------------------------------------------- /src/difference.ts: -------------------------------------------------------------------------------- 1 | // Return the set difference between an array and another array or iterable. 2 | // The results are not sorted in any stable ordering 3 | export function difference(a: T[], b: T[] | IterableIterator): T[] { 4 | const sb = new Set(b); 5 | return Array.from(new Set(a.filter((x) => !sb.has(x))).values()); 6 | } 7 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/sample-robot-docker/start-robot.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | 3 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )" 4 | cd $DIR 5 | 6 | ./build-robot.sh || exit 1 7 | 8 | mkdir -p $HOME/.ros 9 | 10 | docker run \ 11 | -it \ 12 | --rm \ 13 | --net=host \ 14 | -v $HOME/.ros:/home/rosuser/.ros \ 15 | --name sample-robot \ 16 | sample-robot 17 | -------------------------------------------------------------------------------- /src/SubscriberLink.ts: -------------------------------------------------------------------------------- 1 | import { Client } from "./Client"; 2 | 3 | export class SubscriberLink { 4 | readonly connectionId: number; 5 | destinationCallerId: string; 6 | client: Client; 7 | 8 | constructor(connectionId: number, destinationCallerId: string, client: Client) { 9 | this.connectionId = connectionId; 10 | this.destinationCallerId = destinationCallerId; 11 | this.client = client; 12 | } 13 | } 14 | -------------------------------------------------------------------------------- /src/index.ts: -------------------------------------------------------------------------------- 1 | export * from "./Connection"; 2 | export * from "./Publication"; 3 | export * from "./PublisherLink"; 4 | export * from "./RosMasterClient"; 5 | export * from "./RosNode"; 6 | export * from "./RosFollower"; 7 | export * from "./RosFollowerClient"; 8 | export * from "./SubscriberLink"; 9 | export * from "./Subscription"; 10 | export * from "./TcpConnection"; 11 | export * from "./TcpTypes"; 12 | export * from "./XmlRpcTypes"; 13 | -------------------------------------------------------------------------------- /.eslintrc.yaml: -------------------------------------------------------------------------------- 1 | env: 2 | node: true 3 | es2020: true 4 | 5 | ignorePatterns: 6 | - dist 7 | - examples 8 | 9 | extends: 10 | - plugin:@foxglove/base 11 | - plugin:@foxglove/jest 12 | 13 | overrides: 14 | - files: ["*.ts", "*.tsx"] 15 | extends: 16 | - plugin:@foxglove/typescript 17 | parserOptions: 18 | project: [./tsconfig.json, ./tsconfig.dts.json] 19 | rules: 20 | "@typescript-eslint/restrict-template-expressions": off 21 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/sample-robot-docker/Dockerfile: -------------------------------------------------------------------------------- 1 | FROM ros:noetic-robot-focal 2 | 3 | RUN apt-get update && apt-get install -y \ 4 | ros-noetic-ros-tutorials \ 5 | xvfb \ 6 | && rm -rf /var/lib/apt/lists/* 7 | 8 | RUN useradd -ms /bin/bash rosuser 9 | 10 | USER rosuser 11 | ENV HOME=/home/rosuser 12 | WORKDIR /home/rosuser 13 | 14 | COPY entrypoint.sh /home/rosuser/entrypoint.sh 15 | 16 | ENTRYPOINT [ "/bin/bash", "/home/rosuser/entrypoint.sh" ] 17 | -------------------------------------------------------------------------------- /src/Publisher.ts: -------------------------------------------------------------------------------- 1 | import { Client } from "./Client"; 2 | import { Publication } from "./Publication"; 3 | 4 | export interface Publisher { 5 | on( 6 | eventName: "connection", 7 | listener: ( 8 | topic: string, 9 | connectionId: number, 10 | destinationCallerId: string, 11 | client: Client, 12 | ) => void, 13 | ): this; 14 | 15 | publish(publication: Publication, message: unknown): Promise; 16 | 17 | transportType(): string; 18 | 19 | listening(): boolean; 20 | 21 | close(): void; 22 | } 23 | -------------------------------------------------------------------------------- /examples/ros1-chatter/tsconfig.json: -------------------------------------------------------------------------------- 1 | { 2 | "extends": "../../tsconfig.json", 3 | "include": ["src/**/*.ts"], 4 | "compilerOptions": { 5 | "outDir": "dist", 6 | "target": "es2020", 7 | "module": "commonjs", 8 | "lib": ["es2020"], 9 | "importHelpers": true, 10 | "downlevelIteration": true, 11 | "declaration": true, 12 | "rootDir": "./src", 13 | "noImplicitReturns": true, 14 | "noFallthroughCasesInSwitch": true, 15 | "noUnusedLocals": true, 16 | "noUnusedParameters": true, 17 | "noEmit": true 18 | } 19 | } 20 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/tsconfig.json: -------------------------------------------------------------------------------- 1 | { 2 | "extends": "../../tsconfig.json", 3 | "include": ["src/**/*.ts"], 4 | "compilerOptions": { 5 | "outDir": "dist", 6 | "target": "es2020", 7 | "module": "commonjs", 8 | "lib": ["es2020"], 9 | "importHelpers": true, 10 | "downlevelIteration": true, 11 | "declaration": true, 12 | "rootDir": "./src", 13 | "noImplicitReturns": true, 14 | "noFallthroughCasesInSwitch": true, 15 | "noUnusedLocals": true, 16 | "noUnusedParameters": true, 17 | "noEmit": true 18 | } 19 | } 20 | -------------------------------------------------------------------------------- /.vscode/settings.json: -------------------------------------------------------------------------------- 1 | // -*- jsonc -*- 2 | { 3 | "editor.codeActionsOnSave": { 4 | "source.fixAll.eslint": true 5 | }, 6 | "editor.defaultFormatter": "esbenp.prettier-vscode", 7 | "editor.formatOnSave": true, 8 | "files.eol": "\n", 9 | "prettier.prettierPath": "./node_modules/prettier", 10 | "search.exclude": { 11 | "**/node_modules": true, 12 | ".yarn/**": true, 13 | "yarn.lock": true 14 | }, 15 | "typescript.tsdk": "node_modules/typescript/lib", 16 | "eslint.options": { 17 | "reportUnusedDisableDirectives": true 18 | } 19 | } 20 | -------------------------------------------------------------------------------- /src/Client.ts: -------------------------------------------------------------------------------- 1 | export interface ClientStats { 2 | bytesSent: number; 3 | bytesReceived: number; 4 | messagesSent: number; 5 | } 6 | 7 | export interface Client { 8 | on(eventName: "close", listener: () => void): this; 9 | on(eventName: "subscribe", listener: (topic: string, destinationCallerId: string) => void): this; 10 | 11 | transportType(): string; 12 | 13 | connected(): boolean; 14 | 15 | stats(): ClientStats; 16 | 17 | write(data: Uint8Array): Promise; 18 | 19 | close(): void; 20 | 21 | getTransportInfo(): string; 22 | 23 | toString(): string; 24 | } 25 | -------------------------------------------------------------------------------- /.vscode/extensions.json: -------------------------------------------------------------------------------- 1 | // -*- jsonc -*- 2 | { 3 | // See https://go.microsoft.com/fwlink/?LinkId=827846 to learn about workspace recommendations. 4 | // Extension identifier format: ${publisher}.${name}. Example: vscode.csharp 5 | 6 | // List of extensions which should be recommended for users of this workspace. 7 | "recommendations": [ 8 | "dbaeumer.vscode-eslint", 9 | "esbenp.prettier-vscode", 10 | "orta.vscode-jest" 11 | ], 12 | // List of extensions recommended by VS Code that should not be recommended for users of this workspace. 13 | "unwantedRecommendations": [] 14 | } 15 | -------------------------------------------------------------------------------- /src/objectTests.ts: -------------------------------------------------------------------------------- 1 | // Returns true if an object was created by the Object constructor, Object.create(null), or {}. 2 | export function isPlainObject(o: unknown): boolean { 3 | const m = o as Record; 4 | return m != undefined && (m.constructor === Object || m.constructor == undefined); 5 | } 6 | 7 | // Returns true if an object was created by the Object constructor, Object.create(null), or {}, and 8 | // the object does not contain any enumerable keys. 9 | export function isEmptyPlainObject(o: unknown): boolean { 10 | const m = o as Record; 11 | return isPlainObject(m) && Object.keys(m).length === 0; 12 | } 13 | -------------------------------------------------------------------------------- /src/concatData.ts: -------------------------------------------------------------------------------- 1 | export function concatData(chunks: Uint8Array[]): Uint8Array { 2 | if (chunks.length === 1 && chunks[0] != null) { 3 | return chunks[0]; 4 | } 5 | 6 | const totalLength = chunks.reduce((len, chunk) => len + chunk.length, 0); 7 | let result: Uint8Array | undefined; 8 | try { 9 | result = new Uint8Array(totalLength); 10 | } catch (err) { 11 | throw new Error( 12 | `failed to allocate ${totalLength} bytes to concatenate ${chunks.length} chunks`, 13 | ); 14 | } 15 | 16 | let idx = 0; 17 | for (const chunk of chunks) { 18 | result.set(chunk, idx); 19 | idx += chunk.length; 20 | } 21 | return result; 22 | } 23 | -------------------------------------------------------------------------------- /src/nodejs/roscore.ts: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env node 2 | 3 | import { HttpServerNodejs } from "@foxglove/xmlrpc/nodejs"; 4 | 5 | import { getEnvVar, getHostname, getNetworkInterfaces } from "./platform"; 6 | import { RosMaster } from "../RosMaster"; 7 | import { RosNode } from "../RosNode"; 8 | 9 | async function main() { 10 | const hostname = RosNode.GetRosHostname(getEnvVar, getHostname, getNetworkInterfaces); 11 | const port = 11311; 12 | const httpServer = new HttpServerNodejs(); 13 | const rosMaster = new RosMaster(httpServer); 14 | 15 | await rosMaster.start(hostname, port); 16 | console.log(`ROS_MASTER_URI=http://${hostname}:${port}/`); 17 | } 18 | 19 | void main(); 20 | -------------------------------------------------------------------------------- /src/concatData.test.ts: -------------------------------------------------------------------------------- 1 | import { concatData } from "./concatData"; 2 | 3 | describe("concatData", () => { 4 | it("concatData works", () => { 5 | expect(concatData([])).toEqual(new Uint8Array()); 6 | expect(concatData([new Uint8Array([1, 2, 3])])).toEqual(new Uint8Array([1, 2, 3])); 7 | expect(concatData([new Uint8Array([1, 2, 3]), new Uint8Array([4, 5, 6])])).toEqual( 8 | new Uint8Array([1, 2, 3, 4, 5, 6]), 9 | ); 10 | expect( 11 | concatData([ 12 | new Uint8Array([1, 2, 3]), 13 | new Uint8Array([4, 5, 6]), 14 | new Uint8Array(), 15 | new Uint8Array([7]), 16 | ]), 17 | ).toEqual(new Uint8Array([1, 2, 3, 4, 5, 6, 7])); 18 | }); 19 | }); 20 | -------------------------------------------------------------------------------- /src/backoff.test.ts: -------------------------------------------------------------------------------- 1 | import { backoffTime } from "./backoff"; 2 | 3 | describe("backoffTime", () => { 4 | it("works", () => { 5 | expect(backoffTime(0, 60, 100, () => 0.5)).toEqual(51); 6 | expect(backoffTime(1, 60, 100, () => 0.5)).toEqual(52); 7 | expect(backoffTime(2, 60, 100, () => 0.5)).toEqual(54); 8 | expect(backoffTime(3, 60, 100, () => 0.5)).toEqual(58); 9 | expect(backoffTime(4, 60, 100, () => 0.5)).toEqual(60); 10 | 11 | expect(backoffTime(0, 60, 100, () => 0.7)).toEqual(60); 12 | expect(backoffTime(0, 60, 100, () => 0.0)).toEqual(1); 13 | expect(backoffTime(5, 60, 100, () => 0.0)).toEqual(32); 14 | expect(backoffTime(6, 60, 100, () => 0.0)).toEqual(60); 15 | }); 16 | }); 17 | -------------------------------------------------------------------------------- /src/nodejs/platform.ts: -------------------------------------------------------------------------------- 1 | import os from "os"; 2 | 3 | import { NetworkInterface } from "../TcpTypes"; 4 | 5 | export function getPid(): number { 6 | return process.pid; 7 | } 8 | 9 | export function getEnvVar(envVar: string): string | undefined { 10 | return process.env[envVar]; 11 | } 12 | 13 | export function getHostname(): string | undefined { 14 | return os.hostname(); 15 | } 16 | 17 | export function getNetworkInterfaces(): NetworkInterface[] { 18 | const output: NetworkInterface[] = []; 19 | const ifaces = os.networkInterfaces(); 20 | for (const [name, iface] of Object.entries(ifaces)) { 21 | if (iface != undefined) { 22 | for (const info of iface) { 23 | output.push({ name, ...info, cidr: info.cidr ?? undefined }); 24 | } 25 | } 26 | } 27 | return output; 28 | } 29 | -------------------------------------------------------------------------------- /examples/ros1-chatter/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ros1-chatter", 3 | "version": "0.0.0", 4 | "description": "Example @foxglove/ros1 client that publishes to /chatter", 5 | "license": "MIT", 6 | "private": true, 7 | "repository": { 8 | "type": "git", 9 | "url": "https://github.com/foxglove/ros1.git" 10 | }, 11 | "author": { 12 | "name": "Foxglove Technologies Inc", 13 | "email": "contact@foxglove.dev" 14 | }, 15 | "homepage": "https://foxglove.dev/", 16 | "main": "dist/index.js", 17 | "files": [ 18 | "dist" 19 | ], 20 | "scripts": { 21 | "start": "ts-node src/index.ts" 22 | }, 23 | "devDependencies": { 24 | "ts-node": "10.7.0", 25 | "tslib": "2.1.0", 26 | "typescript": "4.5.2" 27 | }, 28 | "dependencies": { 29 | "@foxglove/ros1": "file:../.." 30 | } 31 | } 32 | -------------------------------------------------------------------------------- /.github/workflows/ci.yml: -------------------------------------------------------------------------------- 1 | name: CI 2 | 3 | on: 4 | push: 5 | branches: [main] 6 | tags: ["v*"] 7 | pull_request: 8 | branches: ["*"] 9 | 10 | jobs: 11 | push: 12 | name: push 13 | runs-on: ubuntu-latest 14 | 15 | steps: 16 | - uses: actions/checkout@v3 17 | - uses: actions/setup-node@v3 18 | with: 19 | node-version: 16.x 20 | registry-url: https://registry.npmjs.org 21 | cache: yarn 22 | 23 | - run: yarn install --frozen-lockfile 24 | - run: yarn run build 25 | - run: yarn run lint:ci 26 | - run: yarn run test 27 | 28 | - name: Publish to NPM 29 | if: ${{ startsWith(github.ref, 'refs/tags/v') }} 30 | run: yarn publish --access public 31 | env: 32 | NODE_AUTH_TOKEN: ${{ secrets.NPM_PUBLISH_TOKEN }} 33 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ros1-turtlesim-test", 3 | "version": "0.0.0", 4 | "description": "Example @foxglove/ros1 client that interacts with turtlesim", 5 | "license": "MIT", 6 | "private": true, 7 | "repository": { 8 | "type": "git", 9 | "url": "https://github.com/foxglove/ros1.git" 10 | }, 11 | "author": { 12 | "name": "Foxglove Technologies Inc", 13 | "email": "contact@foxglove.dev" 14 | }, 15 | "homepage": "https://foxglove.dev/", 16 | "main": "dist/index.js", 17 | "files": [ 18 | "dist" 19 | ], 20 | "scripts": { 21 | "start": "ts-node src/index.ts" 22 | }, 23 | "devDependencies": { 24 | "ts-node": "10.7.0", 25 | "tslib": "2.1.0", 26 | "typescript": "4.5.2" 27 | }, 28 | "dependencies": { 29 | "@foxglove/ros1": "file:../.." 30 | } 31 | } 32 | -------------------------------------------------------------------------------- /src/PublisherLink.ts: -------------------------------------------------------------------------------- 1 | import { Connection } from "./Connection"; 2 | import { RosFollowerClient } from "./RosFollowerClient"; 3 | import { Subscription } from "./Subscription"; 4 | 5 | // Handles a connection to a single publisher on a given topic. 6 | export class PublisherLink { 7 | readonly connectionId: number; 8 | readonly subscription: Subscription; 9 | readonly rosFollowerClient: RosFollowerClient; 10 | readonly connection: Connection; 11 | 12 | constructor( 13 | connectionId: number, 14 | subscription: Subscription, 15 | rosFollowerClient: RosFollowerClient, 16 | connection: Connection, 17 | ) { 18 | this.connectionId = connectionId; 19 | this.subscription = subscription; 20 | this.rosFollowerClient = rosFollowerClient; 21 | this.connection = connection; 22 | } 23 | 24 | publisherXmlRpcUrl(): string { 25 | return this.rosFollowerClient.url(); 26 | } 27 | } 28 | -------------------------------------------------------------------------------- /tsconfig.json: -------------------------------------------------------------------------------- 1 | { 2 | "include": ["./src/**/*.ts"], 3 | "compilerOptions": { 4 | "module": "commonjs", 5 | "target": "es2020", 6 | "lib": ["dom", "es2020"], 7 | "rootDir": "./src", 8 | "outDir": "./dist", 9 | 10 | "moduleResolution": "node", 11 | "esModuleInterop": true, 12 | "isolatedModules": true, 13 | "allowJs": false, 14 | "newLine": "lf", 15 | "resolveJsonModule": true, 16 | "skipLibCheck": true, 17 | 18 | "declaration": true, 19 | "declarationMap": true, 20 | "sourceMap": true, 21 | 22 | // be as strict as possible, but no stricter 23 | "strict": true, 24 | "noFallthroughCasesInSwitch": true, 25 | "noImplicitAny": true, 26 | "noImplicitReturns": true, 27 | "noUncheckedIndexedAccess": true, 28 | "noUnusedLocals": true, 29 | "noUnusedParameters": true, 30 | "forceConsistentCasingInFileNames": true 31 | } 32 | } 33 | -------------------------------------------------------------------------------- /src/Connection.ts: -------------------------------------------------------------------------------- 1 | import { MessageDefinition } from "@foxglove/message-definition"; 2 | import { MessageReader } from "@foxglove/rosmsg-serialization"; 3 | 4 | export interface ConnectionStats { 5 | bytesSent: number; 6 | bytesReceived: number; 7 | messagesSent: number; 8 | messagesReceived: number; 9 | dropEstimate: number; 10 | } 11 | 12 | export interface Connection { 13 | on( 14 | eventName: "header", 15 | listener: ( 16 | header: Map, 17 | msgDef: MessageDefinition[], 18 | msgReader: MessageReader, 19 | ) => void, 20 | ): this; 21 | on(eventName: "message", listener: (msg: unknown, data: Uint8Array) => void): this; 22 | on(eventName: "error", listener: (err: Error) => void): this; 23 | 24 | transportType(): string; 25 | 26 | connect(): Promise; 27 | 28 | connected(): boolean; 29 | 30 | header(): Map; 31 | 32 | stats(): ConnectionStats; 33 | 34 | messageDefinition(): MessageDefinition[]; 35 | 36 | messageReader(): MessageReader | undefined; 37 | 38 | close(): void; 39 | 40 | getTransportInfo(): string; 41 | } 42 | -------------------------------------------------------------------------------- /src/mock/MockHttpServer.ts: -------------------------------------------------------------------------------- 1 | import { HttpHandler, HttpServer } from "@foxglove/xmlrpc"; 2 | 3 | export class MockHttpServer implements HttpServer { 4 | handler: HttpHandler = async (_req) => ({ statusCode: 404 }); 5 | 6 | private _port?: number; 7 | private _hostname?: string; 8 | private _defaultHost: string; 9 | private _defaultPort: number; 10 | 11 | constructor(defaultHost: string, defaultPort: number) { 12 | this._defaultHost = defaultHost; 13 | this._defaultPort = defaultPort; 14 | } 15 | 16 | url(): string | undefined { 17 | if (this._hostname == undefined || this._port == undefined) { 18 | return undefined; 19 | } 20 | return `http://${this._hostname}:${this._port}/`; 21 | } 22 | 23 | port(): number | undefined { 24 | return this._port; 25 | } 26 | 27 | async listen(port?: number, hostname?: string, _backlog?: number): Promise { 28 | this._port = port ?? this._defaultPort; 29 | this._hostname = hostname ?? this._defaultHost; 30 | } 31 | 32 | close(): void { 33 | this._port = undefined; 34 | this._hostname = undefined; 35 | } 36 | } 37 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) Foxglove Technologies Inc 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/src/index.ts: -------------------------------------------------------------------------------- 1 | import { RosNode } from "@foxglove/ros1"; 2 | import { 3 | TcpSocketNode, 4 | getEnvVar, 5 | getPid, 6 | getHostname, 7 | getNetworkInterfaces, 8 | } from "@foxglove/ros1/nodejs"; 9 | import { HttpServerNodejs } from "@foxglove/xmlrpc/nodejs"; 10 | 11 | async function main() { 12 | const name = "/testclient"; 13 | let rosNode: RosNode | undefined; 14 | 15 | try { 16 | const hostname = RosNode.GetRosHostname(getEnvVar, getHostname, getNetworkInterfaces); 17 | rosNode = new RosNode({ 18 | name, 19 | rosMasterUri: getEnvVar("ROS_MASTER_URI") ?? "http://localhost:11311/", 20 | hostname, 21 | pid: getPid(), 22 | httpServer: new HttpServerNodejs(), 23 | tcpSocketCreate: TcpSocketNode.Create, 24 | log: console, 25 | }); 26 | 27 | await rosNode.start(); 28 | 29 | const sub = rosNode.subscribe({ 30 | topic: "/turtle1/color_sensor", 31 | dataType: "turtlesim/Color", 32 | }); 33 | console.dir(sub.getStats()); 34 | } catch (err) { 35 | const msg = (err as Error).stack ?? `${err}`; 36 | console.error(msg); 37 | } finally { 38 | rosNode?.shutdown(); 39 | } 40 | } 41 | 42 | void main(); 43 | -------------------------------------------------------------------------------- /src/backoff.ts: -------------------------------------------------------------------------------- 1 | // Implements truncated exponential backoff with jitter. Each retry, the backoff 2 | // time is increased by 2^retries plus a random amount of jitter. The maximum 3 | // time returned by this method is capped at `maxMs`. 4 | export function backoffTime( 5 | retries: number, 6 | maxMs = 10000, 7 | maxJitterMs = 1000, 8 | rng: () => number = Math.random, 9 | ): number { 10 | const randomMs = rng() * maxJitterMs; 11 | return Math.min(Math.pow(2, retries) + randomMs, maxMs); 12 | } 13 | 14 | // Wait for a period of time determined by the truncated exponential backoff 15 | // with jitter algorithm implemented in `backoffTime()`. 16 | export async function backoff( 17 | retries: number, 18 | maxMs = 10000, 19 | maxJitterMs = 1000, 20 | rng: () => number = Math.random, 21 | ): Promise { 22 | return await new Promise((resolve) => 23 | setTimeout(resolve, backoffTime(retries, maxMs, maxJitterMs, rng)), 24 | ); 25 | } 26 | 27 | // Continue to call an async function until it completes without throwing an 28 | // exception 29 | export async function retryForever(fn: () => Promise): Promise { 30 | let retries = 0; 31 | // eslint-disable-next-line no-constant-condition 32 | while (true) { 33 | try { 34 | return await fn(); 35 | } catch (err) { 36 | await backoff(++retries); 37 | } 38 | } 39 | } 40 | -------------------------------------------------------------------------------- /src/RosMaster.test.ts: -------------------------------------------------------------------------------- 1 | import { RosMaster } from "./RosMaster"; 2 | import { MockHttpServer } from "./mock/MockHttpServer"; 3 | 4 | const CALLER_ID1 = "/test1"; 5 | const CALLER_API1 = "http://127.0.0.1:1111/"; 6 | 7 | const CALLER_ID2 = "/test2"; 8 | const CALLER_API2 = "http://127.0.0.1:1112/"; 9 | 10 | describe("RosMaster", () => { 11 | it("registers publishers", async () => { 12 | const rosMaster = new RosMaster(new MockHttpServer("127.0.0.1", 11311)); 13 | let res = await rosMaster.registerPublisher("registerPublisher", [ 14 | CALLER_ID1, 15 | "/a", 16 | "testType", 17 | CALLER_API1, 18 | ]); 19 | expect(Array.isArray(res)).toBe(true); 20 | expect(res).toHaveLength(3); 21 | 22 | const [status, msg, subscribers] = res; 23 | expect(status).toEqual(1); 24 | expect(typeof msg).toBe("string"); 25 | expect(Array.isArray(subscribers)).toBe(true); 26 | expect(subscribers).toHaveLength(0); 27 | 28 | res = await rosMaster.registerSubscriber("registerSubscriber", [ 29 | CALLER_ID2, 30 | "/a", 31 | "testType", 32 | CALLER_API2, 33 | ]); 34 | expect(Array.isArray(res)).toBe(true); 35 | expect(res).toHaveLength(3); 36 | 37 | const [status2, msg2, publishers] = res; 38 | expect(status2).toEqual(1); 39 | expect(typeof msg2).toBe("string"); 40 | expect(Array.isArray(publishers)).toBe(true); 41 | expect(publishers).toEqual([CALLER_API1]); 42 | 43 | rosMaster.close(); 44 | }); 45 | }); 46 | -------------------------------------------------------------------------------- /examples/ros1-chatter/src/index.ts: -------------------------------------------------------------------------------- 1 | import { RosNode } from "@foxglove/ros1"; 2 | import { 3 | TcpServerNode, 4 | TcpSocketNode, 5 | getEnvVar, 6 | getPid, 7 | getHostname, 8 | getNetworkInterfaces, 9 | } from "@foxglove/ros1/nodejs"; 10 | import { HttpServerNodejs } from "@foxglove/xmlrpc/nodejs"; 11 | 12 | async function main() { 13 | const name = "/ros1-chatter"; 14 | let rosNode: RosNode | undefined; 15 | 16 | try { 17 | const hostname = RosNode.GetRosHostname(getEnvVar, getHostname, getNetworkInterfaces); 18 | const tcpServer = await TcpServerNode.Listen({ host: hostname }); 19 | rosNode = new RosNode({ 20 | name, 21 | rosMasterUri: getEnvVar("ROS_MASTER_URI") ?? "http://localhost:11311/", 22 | hostname, 23 | pid: getPid(), 24 | httpServer: new HttpServerNodejs(), 25 | tcpSocketCreate: TcpSocketNode.Create, 26 | tcpServer, 27 | log: console, 28 | }); 29 | 30 | await rosNode.start(); 31 | 32 | await rosNode.advertise({ 33 | topic: "/chatter", 34 | dataType: "std_msgs/String", 35 | latching: true, 36 | messageDefinition: [{ definitions: [{ name: "data", type: "string" }] }], 37 | messageDefinitionText: "string data", 38 | md5sum: "992ce8a1687cec8c8bd883ec73ca41d1", 39 | }); 40 | 41 | let running = true; 42 | process.on("SIGINT", () => (running = false)); 43 | 44 | while (running) { 45 | void rosNode.publish("/chatter", { data: "Hello, world!" }); 46 | await new Promise((resolve) => setTimeout(resolve, 1000)); 47 | } 48 | } catch (err) { 49 | const msg = (err as Error).stack ?? `${err}`; 50 | console.error(msg); 51 | } finally { 52 | rosNode?.shutdown(); 53 | } 54 | } 55 | 56 | void main(); 57 | -------------------------------------------------------------------------------- /src/nodejs/TcpServerNode.ts: -------------------------------------------------------------------------------- 1 | import EventEmitter from "eventemitter3"; 2 | import net from "net"; 3 | 4 | import { TcpSocketNode } from "./TcpSocketNode"; 5 | import { TcpAddress, TcpServer, TcpServerEvents } from "../TcpTypes"; 6 | 7 | export class TcpServerNode extends EventEmitter implements TcpServer { 8 | private _server: net.Server; 9 | 10 | constructor(server: net.Server) { 11 | super(); 12 | this._server = server; 13 | 14 | server.on("close", () => this.emit("close")); 15 | server.on("connection", (socket) => { 16 | const host = socket.remoteAddress; 17 | const port = socket.remotePort; 18 | if (host != undefined && port != undefined) { 19 | this.emit("connection", new TcpSocketNode(host, port, socket)); 20 | } 21 | }); 22 | server.on("error", (err) => this.emit("error", err)); 23 | } 24 | 25 | async address(): Promise { 26 | const addr = this._server.address(); 27 | if (addr == undefined || typeof addr === "string") { 28 | // Address will only be a string for an IPC (named pipe) server, which 29 | // should never happen in TcpServerNode 30 | return undefined; 31 | } 32 | return addr; 33 | } 34 | 35 | close(): void { 36 | this._server.close(); 37 | } 38 | 39 | static async Listen(options: { 40 | host?: string; 41 | port?: number; 42 | backlog?: number; 43 | }): Promise { 44 | return await new Promise((resolve, reject) => { 45 | const server = net.createServer(); 46 | server.on("error", reject); 47 | server.listen(options.port, options.host, options.backlog, () => { 48 | server.removeListener("error", reject); 49 | resolve(new TcpServerNode(server)); 50 | }); 51 | }); 52 | } 53 | } 54 | -------------------------------------------------------------------------------- /src/RosXmlRpcClient.ts: -------------------------------------------------------------------------------- 1 | import { XmlRpcClient, XmlRpcFault, XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | import { RosXmlRpcResponse, RosXmlRpcResponseOrFault } from "./XmlRpcTypes"; 4 | 5 | export class RosXmlRpcClient { 6 | private _client: XmlRpcClient; 7 | 8 | constructor(url: string) { 9 | this._client = new XmlRpcClient(url, { encoding: "utf-8" }); 10 | } 11 | 12 | url(): string { 13 | return this._client.url; 14 | } 15 | 16 | protected _methodCall = async ( 17 | methodName: string, 18 | args: XmlRpcValue[], 19 | ): Promise => { 20 | const res = await this._client.methodCall(methodName, args); 21 | if (!Array.isArray(res) || res.length !== 3) { 22 | throw new Error(`Malformed XML-RPC response`); 23 | } 24 | 25 | const [code, msg] = res; 26 | if (typeof code !== "number" || typeof msg !== "string") { 27 | throw new Error(`Invalid code/msg, code="${code}", msg="${msg}"`); 28 | } 29 | return res as RosXmlRpcResponse; 30 | }; 31 | 32 | protected _multiMethodCall = async ( 33 | requests: { methodName: string; params: XmlRpcValue[] }[], 34 | ): Promise => { 35 | const res = await this._client.multiMethodCall(requests); 36 | 37 | const output: RosXmlRpcResponseOrFault[] = []; 38 | for (const entry of res) { 39 | if (entry instanceof XmlRpcFault) { 40 | output.push(entry); 41 | } else if (!Array.isArray(entry) || entry.length !== 3) { 42 | throw new Error(`Malformed XML-RPC multicall response`); 43 | } else { 44 | const [code, msg] = entry; 45 | if (typeof code !== "number" || typeof msg !== "string") { 46 | throw new Error(`Invalid code/msg, code="${code}", msg="${msg}"`); 47 | } 48 | output.push(entry as RosXmlRpcResponse); 49 | } 50 | } 51 | return output; 52 | }; 53 | } 54 | -------------------------------------------------------------------------------- /src/objectTests.test.ts: -------------------------------------------------------------------------------- 1 | import { isEmptyPlainObject, isPlainObject } from "./objectTests"; 2 | 3 | class NonPlainObject {} 4 | 5 | describe("isPlainObject", () => { 6 | it("works", () => { 7 | expect(isPlainObject(undefined)).toEqual(false); 8 | expect(isPlainObject(null)).toEqual(false); 9 | expect(isPlainObject("")).toEqual(false); 10 | expect(isPlainObject("a")).toEqual(false); 11 | expect(isPlainObject(0)).toEqual(false); 12 | expect(isPlainObject(1)).toEqual(false); 13 | expect(isPlainObject(false)).toEqual(false); 14 | expect(isPlainObject(true)).toEqual(false); 15 | expect(isPlainObject(new Date())).toEqual(false); 16 | expect(isPlainObject(new NonPlainObject())).toEqual(false); 17 | 18 | expect(isPlainObject({})).toEqual(true); 19 | expect(isPlainObject({ a: 1 })).toEqual(true); 20 | expect(isPlainObject(new Object())).toEqual(true); 21 | expect(isPlainObject(Object.create(null))).toEqual(true); 22 | }); 23 | }); 24 | 25 | describe("isEmptyPlainObject", () => { 26 | it("works", () => { 27 | expect(isEmptyPlainObject(undefined)).toEqual(false); 28 | expect(isEmptyPlainObject(null)).toEqual(false); 29 | expect(isEmptyPlainObject("")).toEqual(false); 30 | expect(isEmptyPlainObject("a")).toEqual(false); 31 | expect(isEmptyPlainObject(0)).toEqual(false); 32 | expect(isEmptyPlainObject(1)).toEqual(false); 33 | expect(isEmptyPlainObject(false)).toEqual(false); 34 | expect(isEmptyPlainObject(true)).toEqual(false); 35 | expect(isEmptyPlainObject(new Date())).toEqual(false); 36 | expect(isEmptyPlainObject(new NonPlainObject())).toEqual(false); 37 | 38 | expect(isEmptyPlainObject({})).toEqual(true); 39 | expect(isEmptyPlainObject({ a: 1 })).toEqual(false); 40 | expect(isEmptyPlainObject(new Object())).toEqual(true); 41 | expect(isEmptyPlainObject(Object.create(null))).toEqual(true); 42 | }); 43 | }); 44 | -------------------------------------------------------------------------------- /src/RosFollowerClient.ts: -------------------------------------------------------------------------------- 1 | import { XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | import { RosXmlRpcClient } from "./RosXmlRpcClient"; 4 | import { RosXmlRpcResponse } from "./XmlRpcTypes"; 5 | 6 | export type ProtocolParams = [string, ...XmlRpcValue[]]; 7 | 8 | export class RosFollowerClient extends RosXmlRpcClient { 9 | async getBusStats(callerId: string): Promise { 10 | return await this._methodCall("getBusStats", [callerId]); 11 | } 12 | 13 | async getBusInfo(callerId: string): Promise { 14 | return await this._methodCall("getBusInfo", [callerId]); 15 | } 16 | 17 | async shutdown(callerId: string, msg = ""): Promise { 18 | return await this._methodCall("shutdown", [callerId, msg]); 19 | } 20 | 21 | async getPid(callerId: string): Promise { 22 | return await this._methodCall("getPid", [callerId]); 23 | } 24 | 25 | async getSubscriptions(callerId: string): Promise { 26 | return await this._methodCall("getSubscriptions", [callerId]); 27 | } 28 | 29 | async getPublications(callerId: string): Promise { 30 | return await this._methodCall("getPublications", [callerId]); 31 | } 32 | 33 | async paramUpdate( 34 | callerId: string, 35 | parameterKey: string, 36 | parameterValue: XmlRpcValue, 37 | ): Promise { 38 | return await this._methodCall("paramUpdate", [callerId, parameterKey, parameterValue]); 39 | } 40 | 41 | async publisherUpdate( 42 | callerId: string, 43 | topic: string, 44 | publishers: string[], 45 | ): Promise { 46 | return await this._methodCall("publisherUpdate", [callerId, topic, publishers]); 47 | } 48 | 49 | async requestTopic( 50 | callerId: string, 51 | topic: string, 52 | protocols: ProtocolParams[], 53 | ): Promise { 54 | return await this._methodCall("requestTopic", [callerId, topic, protocols]); 55 | } 56 | } 57 | -------------------------------------------------------------------------------- /src/TcpTypes.ts: -------------------------------------------------------------------------------- 1 | export type TcpAddress = { 2 | port: number; 3 | family?: string; 4 | address: string; 5 | }; 6 | 7 | export interface NetworkInterface { 8 | name: string; 9 | family: "IPv4" | "IPv6"; 10 | internal: boolean; 11 | address: string; 12 | cidr?: string; 13 | mac: string; 14 | netmask: string; 15 | } 16 | 17 | export interface TcpSocketEvents { 18 | connect: () => void; 19 | close: () => void; 20 | data: (data: Uint8Array) => void; 21 | end: () => void; 22 | timeout: () => void; 23 | error: (err: Error) => void; 24 | } 25 | 26 | export interface TcpSocket { 27 | remoteAddress(): Promise; 28 | localAddress(): Promise; 29 | fd(): Promise; 30 | connected(): Promise; 31 | 32 | connect(): Promise; 33 | close(): Promise; 34 | write(data: Uint8Array): Promise; 35 | setNoDelay(noDelay?: boolean): Promise; 36 | 37 | on(eventName: "connect", listener: () => void): this; 38 | on(eventName: "close", listener: () => void): this; 39 | on(eventName: "data", listener: (data: Uint8Array) => void): this; 40 | on(eventName: "end", listener: () => void): this; 41 | on(eventName: "timeout", listener: () => void): this; 42 | on(eventName: "error", listener: (err: Error) => void): this; 43 | } 44 | 45 | export interface TcpServerEvents { 46 | close: () => void; 47 | connection: (socket: TcpSocket) => void; 48 | error: (err: Error) => void; 49 | } 50 | 51 | export interface TcpServer { 52 | address(): Promise; 53 | close(): void; 54 | 55 | on(eventName: "close", listener: () => void): this; 56 | on(eventName: "connection", listener: (socket: TcpSocket) => void): this; 57 | on(eventName: "error", listener: (err: Error) => void): this; 58 | } 59 | 60 | export interface TcpListen { 61 | (options: { host?: string; port?: number; backlog?: number }): Promise; 62 | } 63 | 64 | export interface TcpSocketCreate { 65 | (options: { host: string; port: number }): Promise; 66 | } 67 | -------------------------------------------------------------------------------- /src/mock/MockTcp.ts: -------------------------------------------------------------------------------- 1 | import { EventEmitter } from "eventemitter3"; 2 | 3 | import { TcpAddress, TcpServer, TcpServerEvents, TcpSocket, TcpSocketEvents } from "../TcpTypes"; 4 | 5 | export class MockTcpSocket extends EventEmitter implements TcpSocket { 6 | private _connected = true; 7 | 8 | constructor() { 9 | super(); 10 | } 11 | 12 | async remoteAddress(): Promise { 13 | return { 14 | address: "192.168.1.2", 15 | port: 40000, 16 | family: this._connected ? "IPv4" : undefined, 17 | }; 18 | } 19 | 20 | async localAddress(): Promise { 21 | return this._connected ? { address: "127.0.0.1", port: 30000, family: "IPv4" } : undefined; 22 | } 23 | 24 | async fd(): Promise { 25 | return 1; 26 | } 27 | 28 | async connected(): Promise { 29 | return this._connected; 30 | } 31 | 32 | async connect(): Promise { 33 | // no-op 34 | } 35 | 36 | async close(): Promise { 37 | this._connected = false; 38 | } 39 | 40 | async write(_data: Uint8Array): Promise { 41 | // no-op 42 | } 43 | 44 | // eslint-disable-next-line @foxglove/no-boolean-parameters 45 | async setNoDelay(_noDelay?: boolean): Promise { 46 | // no-op 47 | } 48 | } 49 | 50 | export class MockTcpServer extends EventEmitter implements TcpServer { 51 | listening = true; 52 | 53 | constructor() { 54 | super(); 55 | } 56 | 57 | async address(): Promise { 58 | return this.listening ? { address: "192.168.1.1", port: 20000, family: "IPv4" } : undefined; 59 | } 60 | 61 | close(): void { 62 | this.listening = false; 63 | } 64 | } 65 | 66 | export async function TcpListen(_options: { 67 | host?: string; 68 | port?: number; 69 | backlog?: number; 70 | }): Promise { 71 | return new MockTcpServer(); 72 | } 73 | 74 | export async function TcpSocketConnect(_options: { 75 | host: string; 76 | port: number; 77 | }): Promise { 78 | return new MockTcpSocket(); 79 | } 80 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Logs 2 | logs 3 | *.log 4 | npm-debug.log* 5 | yarn-debug.log* 6 | yarn-error.log* 7 | lerna-debug.log* 8 | 9 | # Diagnostic reports (https://nodejs.org/api/report.html) 10 | report.[0-9]*.[0-9]*.[0-9]*.[0-9]*.json 11 | 12 | # Runtime data 13 | pids 14 | *.pid 15 | *.seed 16 | *.pid.lock 17 | 18 | # Directory for instrumented libs generated by jscoverage/JSCover 19 | lib-cov 20 | 21 | # Coverage directory used by tools like istanbul 22 | coverage 23 | *.lcov 24 | 25 | # nyc test coverage 26 | .nyc_output 27 | 28 | # Grunt intermediate storage (https://gruntjs.com/creating-plugins#storing-task-files) 29 | .grunt 30 | 31 | # Bower dependency directory (https://bower.io/) 32 | bower_components 33 | 34 | # node-waf configuration 35 | .lock-wscript 36 | 37 | # Compiled binary addons (https://nodejs.org/api/addons.html) 38 | build/Release 39 | 40 | # Dependency directories 41 | node_modules/ 42 | jspm_packages/ 43 | 44 | # TypeScript v1 declaration files 45 | typings/ 46 | 47 | # TypeScript cache 48 | *.tsbuildinfo 49 | 50 | # Optional npm cache directory 51 | .npm 52 | 53 | # Optional eslint cache 54 | .eslintcache 55 | 56 | # Microbundle cache 57 | .rpt2_cache/ 58 | .rts2_cache_cjs/ 59 | .rts2_cache_es/ 60 | .rts2_cache_umd/ 61 | 62 | # Optional REPL history 63 | .node_repl_history 64 | 65 | # Output of 'npm pack' 66 | *.tgz 67 | 68 | # Yarn Integrity file 69 | .yarn-integrity 70 | 71 | # dotenv environment variables file 72 | .env 73 | .env.test 74 | 75 | # parcel-bundler cache (https://parceljs.org/) 76 | .cache 77 | 78 | # Next.js build output 79 | .next 80 | 81 | # Nuxt.js build / generate output 82 | .nuxt 83 | dist 84 | 85 | # Gatsby files 86 | .cache/ 87 | # Comment in the public line in if your project uses Gatsby and *not* Next.js 88 | # https://nextjs.org/blog/next-9-1#public-directory-support 89 | # public 90 | 91 | # vuepress build output 92 | .vuepress/dist 93 | 94 | # Serverless directories 95 | .serverless/ 96 | 97 | # FuseBox cache 98 | .fusebox/ 99 | 100 | # DynamoDB Local files 101 | .dynamodb/ 102 | 103 | # TernJS port file 104 | .tern-port 105 | 106 | # MacOS 107 | .DS_Store 108 | -------------------------------------------------------------------------------- /package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "@foxglove/ros1", 3 | "version": "3.0.0", 4 | "description": "Standalone TypeScript implementation of the ROS 1 (Robot Operating System) protocol with a pluggable transport layer", 5 | "license": "MIT", 6 | "keywords": [ 7 | "ros", 8 | "ros1", 9 | "robot", 10 | "operating", 11 | "system", 12 | "tcp", 13 | "protocol", 14 | "sockets" 15 | ], 16 | "repository": { 17 | "type": "git", 18 | "url": "https://github.com/foxglove/ros1.git" 19 | }, 20 | "author": { 21 | "name": "Foxglove Technologies Inc", 22 | "email": "contact@foxglove.dev" 23 | }, 24 | "homepage": "https://github.com/foxglove/ros1", 25 | "main": "dist/index.js", 26 | "typings": "dist/index.d.ts", 27 | "exports": { 28 | ".": "./dist/index.js", 29 | "./nodejs": "./dist/nodejs/index.js" 30 | }, 31 | "files": [ 32 | "dist", 33 | "src", 34 | "nodejs.d.ts", 35 | "nodejs.js" 36 | ], 37 | "bin": { 38 | "roscore": "./dist/nodejs/roscore.js" 39 | }, 40 | "scripts": { 41 | "build": "tsc -b", 42 | "lint:ci": "eslint --report-unused-disable-directives .", 43 | "lint": "eslint --report-unused-disable-directives --fix .", 44 | "prepack": "yarn build", 45 | "prepublishOnly": "yarn lint:ci && yarn test", 46 | "test": "jest", 47 | "roscore": "node -r esbuild-runner/register src/nodejs/roscore.ts" 48 | }, 49 | "engines": { 50 | "node": ">= 14" 51 | }, 52 | "devDependencies": { 53 | "@foxglove/eslint-plugin": "0.21.0", 54 | "@types/jest": "^29.4.0", 55 | "@typescript-eslint/eslint-plugin": "5.54.0", 56 | "@typescript-eslint/parser": "5.54.0", 57 | "esbuild": "0.17.10", 58 | "esbuild-runner": "2.2.2", 59 | "eslint": "8.35.0", 60 | "eslint-config-prettier": "8.6.0", 61 | "eslint-plugin-es": "4.1.0", 62 | "eslint-plugin-filenames": "1.3.2", 63 | "eslint-plugin-import": "2.27.5", 64 | "eslint-plugin-jest": "27.2.1", 65 | "eslint-plugin-prettier": "4.2.1", 66 | "jest": "29.4.3", 67 | "prettier": "2.8.4", 68 | "ts-jest": "29.0.5", 69 | "typescript": "4.9.5" 70 | }, 71 | "dependencies": { 72 | "@foxglove/message-definition": "^0.2.0", 73 | "@foxglove/rosmsg": "^4.0.0", 74 | "@foxglove/rosmsg-serialization": "^2.0.0", 75 | "@foxglove/xmlrpc": "^1.3.0", 76 | "eventemitter3": "^5.0.0", 77 | "ipaddr.js": "^2.0.1" 78 | } 79 | } 80 | -------------------------------------------------------------------------------- /src/RosParamClient.ts: -------------------------------------------------------------------------------- 1 | import { XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | import { RosXmlRpcClient } from "./RosXmlRpcClient"; 4 | import { RosXmlRpcResponse, RosXmlRpcResponseOrFault } from "./XmlRpcTypes"; 5 | 6 | export class RosParamClient extends RosXmlRpcClient { 7 | async deleteParam(callerId: string, key: string): Promise { 8 | return await this._methodCall("deleteParam", [callerId, key]); 9 | } 10 | 11 | async setParam(callerId: string, key: string, value: XmlRpcValue): Promise { 12 | return await this._methodCall("setParam", [callerId, key, value]); 13 | } 14 | 15 | async getParam(callerId: string, key: string): Promise { 16 | return await this._methodCall("getParam", [callerId, key]); 17 | } 18 | 19 | async searchParam(callerId: string, key: string): Promise { 20 | return await this._methodCall("searchParam", [callerId, key]); 21 | } 22 | 23 | async subscribeParam( 24 | callerId: string, 25 | callerApi: string, 26 | key: string, 27 | ): Promise { 28 | return await this._methodCall("subscribeParam", [callerId, callerApi, key]); 29 | } 30 | 31 | async subscribeParams( 32 | callerId: string, 33 | callerApi: string, 34 | keys: string[], 35 | ): Promise { 36 | const requests = keys.map((key) => ({ 37 | methodName: "subscribeParam", 38 | params: [callerId, callerApi, key], 39 | })); 40 | return await this._multiMethodCall(requests); 41 | } 42 | 43 | async unsubscribeParam( 44 | callerId: string, 45 | callerApi: string, 46 | key: string, 47 | ): Promise { 48 | return await this._methodCall("unsubscribeParam", [callerId, callerApi, key]); 49 | } 50 | 51 | async unsubscribeParams( 52 | callerId: string, 53 | callerApi: string, 54 | keys: string[], 55 | ): Promise { 56 | const requests = keys.map((key) => ({ 57 | methodName: "unsubscribeParam", 58 | params: [callerId, callerApi, key], 59 | })); 60 | return await this._multiMethodCall(requests); 61 | } 62 | 63 | async hasParam(callerId: string, key: string): Promise { 64 | return await this._methodCall("hasParam", [callerId, key]); 65 | } 66 | 67 | async getParamNames(callerId: string): Promise { 68 | return await this._methodCall("getParamNames", [callerId]); 69 | } 70 | } 71 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # @foxglove/ros1 2 | 3 | > [!IMPORTANT] 4 | > This package has moved to https://github.com/foxglove/ros-typescript. 5 | 6 | > _Standalone TypeScript implementation of the ROS 1 (Robot Operating System) protocol with a pluggable transport layer_ 7 | 8 | [![npm version](https://img.shields.io/npm/v/@foxglove/ros1.svg?style=flat)](https://www.npmjs.com/package/@foxglove/ros1) 9 | 10 | ## Usage 11 | 12 | ```Typescript 13 | // An example client that connects to the ROS1 turtlesim node 14 | 15 | import { RosNode } from "@foxglove/ros1"; 16 | import { getEnvVar, getHostname, getNetworkInterfaces, getPid, TcpSocketNode } from "@foxglove/ros1/nodejs"; 17 | import { HttpServerNodejs } from "@foxglove/xmlrpc/nodejs"; 18 | 19 | async function main() { 20 | const name = "/testclient"; 21 | let rosNode: RosNode | undefined; 22 | 23 | try { 24 | rosNode = new RosNode({ 25 | name, 26 | rosMasterUri: getEnvVar("ROS_MASTER_URI") ?? "http://localhost:11311/", 27 | hostname: RosNode.GetRosHostname(getEnvVar, getHostname, getNetworkInterfaces), 28 | pid: getPid(), 29 | httpServer: new HttpServerNodejs(), 30 | tcpSocketCreate: TcpSocketNode.Create, 31 | log: console, 32 | }); 33 | 34 | await rosNode.start(); 35 | 36 | const params = await rosNode.subscribeAllParams(); 37 | console.dir(params); 38 | 39 | const sub = rosNode.subscribe({ 40 | topic: "/turtle1/color_sensor", 41 | dataType: "turtlesim/Color", 42 | }); 43 | 44 | sub.on("message", (msg, data, pub) => { 45 | console.log( 46 | `[MSG] ${JSON.stringify(msg)} (${ 47 | data.byteLength 48 | } bytes from ${pub.connection.getTransportInfo()})`, 49 | ); 50 | }); 51 | 52 | await new Promise((resolve) => setTimeout(resolve, 1000)); 53 | 54 | console.dir(sub.getStats()); 55 | } catch (err) { 56 | const msg = (err as Error).stack ?? `${err}`; 57 | console.error(msg); 58 | } finally { 59 | rosNode?.shutdown(); 60 | } 61 | } 62 | 63 | void main(); 64 | ``` 65 | 66 | ### Test 67 | 68 | `yarn test` 69 | 70 | ## License 71 | 72 | @foxglove/ros1 is licensed under the [MIT License](https://opensource.org/licenses/MIT). 73 | 74 | ## Releasing 75 | 76 | 1. Run `yarn version --[major|minor|patch]` to bump version 77 | 2. Run `git push && git push --tags` to push new tag 78 | 3. GitHub Actions will take care of the rest 79 | 80 | ## Stay in touch 81 | 82 | Join our [Slack channel](https://foxglove.dev/slack) to ask questions, share feedback, and stay up to date on what our team is working on. 83 | 84 | -------------------------------------------------------------------------------- /src/RosTcpMessageStream.ts: -------------------------------------------------------------------------------- 1 | import { EventEmitter } from "eventemitter3"; 2 | 3 | import { concatData } from "./concatData"; 4 | 5 | // This is the maximum message length allowed by ros_comm. See 6 | // 7 | const MAX_MSG_LENGTH = 1000000000; 8 | 9 | export interface RosTcpMessageStreamEvents { 10 | message: (message: Uint8Array) => void; 11 | } 12 | 13 | // A stateful transformer that takes a raw TCPROS data stream and parses the 14 | // TCPROS format of 4 byte length prefixes followed by message payloads into one 15 | // complete message per "message" event, discarding the length prefix 16 | export class RosTcpMessageStream extends EventEmitter { 17 | private _inMessage = false; 18 | private _bytesNeeded = 4; 19 | private _chunks: Uint8Array[] = []; 20 | 21 | addData(chunk: Uint8Array): void { 22 | let idx = 0; 23 | while (idx < chunk.length) { 24 | if (chunk.length - idx < this._bytesNeeded) { 25 | // If we didn't receive enough bytes to complete the current message or 26 | // message length field, store this chunk and continue on 27 | this._chunks.push(new Uint8Array(chunk.buffer, chunk.byteOffset + idx)); 28 | this._bytesNeeded -= chunk.length - idx; 29 | return; 30 | } 31 | 32 | // Store the final chunk needed to complete the current message or message 33 | // length field 34 | this._chunks.push(new Uint8Array(chunk.buffer, chunk.byteOffset + idx, this._bytesNeeded)); 35 | idx += this._bytesNeeded; 36 | 37 | const payload = concatData(this._chunks); 38 | this._chunks = []; 39 | 40 | if (this._inMessage) { 41 | // Produce a Uint8Array representing a single message and transition to 42 | // reading a message length field 43 | this._bytesNeeded = 4; 44 | this.emit("message", payload); 45 | this._inMessage = false; 46 | } else { 47 | // Decode the message length field and transition to reading a message 48 | this._bytesNeeded = new DataView( 49 | payload.buffer, 50 | payload.byteOffset, 51 | payload.byteLength, 52 | ).getUint32(0, true); 53 | 54 | if (this._bytesNeeded > MAX_MSG_LENGTH) { 55 | throw new Error(`Invalid message length of ${this._bytesNeeded} decoded in a tcp stream`); 56 | } else if (this._bytesNeeded === 0) { 57 | this._bytesNeeded = 4; 58 | this.emit("message", new Uint8Array()); 59 | } else { 60 | this._inMessage = true; 61 | } 62 | } 63 | } 64 | } 65 | } 66 | -------------------------------------------------------------------------------- /src/RosMasterClient.ts: -------------------------------------------------------------------------------- 1 | import { RosXmlRpcClient } from "./RosXmlRpcClient"; 2 | import { RosXmlRpcResponse } from "./XmlRpcTypes"; 3 | 4 | export class RosMasterClient extends RosXmlRpcClient { 5 | async registerService( 6 | callerId: string, 7 | service: string, 8 | serviceApi: string, 9 | callerApi: string, 10 | ): Promise { 11 | return await this._methodCall("registerService", [callerId, service, serviceApi, callerApi]); 12 | } 13 | 14 | async unregisterService( 15 | callerId: string, 16 | service: string, 17 | serviceApi: string, 18 | ): Promise { 19 | return await this._methodCall("unregisterService", [callerId, service, serviceApi]); 20 | } 21 | 22 | async registerSubscriber( 23 | callerId: string, 24 | topic: string, 25 | topicType: string, 26 | callerApi: string, 27 | ): Promise { 28 | return await this._methodCall("registerSubscriber", [callerId, topic, topicType, callerApi]); 29 | } 30 | 31 | async unregisterSubscriber( 32 | callerId: string, 33 | topic: string, 34 | callerApi: string, 35 | ): Promise { 36 | return await this._methodCall("unregisterSubscriber", [callerId, topic, callerApi]); 37 | } 38 | 39 | async registerPublisher( 40 | callerId: string, 41 | topic: string, 42 | topicType: string, 43 | callerApi: string, 44 | ): Promise { 45 | return await this._methodCall("registerPublisher", [callerId, topic, topicType, callerApi]); 46 | } 47 | 48 | async unregisterPublisher( 49 | callerId: string, 50 | topic: string, 51 | callerApi: string, 52 | ): Promise { 53 | return await this._methodCall("unregisterPublisher", [callerId, topic, callerApi]); 54 | } 55 | 56 | async lookupNode(callerId: string, nodeName: string): Promise { 57 | return await this._methodCall("lookupNode", [callerId, nodeName]); 58 | } 59 | 60 | async getPublishedTopics(callerId: string, subgraph = ""): Promise { 61 | return await this._methodCall("getPublishedTopics", [callerId, subgraph]); 62 | } 63 | 64 | async getTopicTypes(callerId: string): Promise { 65 | return await this._methodCall("getTopicTypes", [callerId]); 66 | } 67 | 68 | async getSystemState(callerId: string): Promise { 69 | return await this._methodCall("getSystemState", [callerId]); 70 | } 71 | 72 | async getUri(callerId: string): Promise { 73 | return await this._methodCall("getUri", [callerId]); 74 | } 75 | 76 | async lookupService(callerId: string, service: string): Promise { 77 | return await this._methodCall("lookupService", [callerId, service]); 78 | } 79 | } 80 | -------------------------------------------------------------------------------- /src/RosTcpMessageStream.test.ts: -------------------------------------------------------------------------------- 1 | import { RosTcpMessageStream } from "./RosTcpMessageStream"; 2 | 3 | describe("RosTcpMessageStream", () => { 4 | it("decodes an empty message", () => { 5 | const stream = new RosTcpMessageStream(); 6 | 7 | let curMsg: Uint8Array | undefined; 8 | stream.on("message", (msg) => (curMsg = msg)); 9 | 10 | stream.addData(new Uint8Array()); 11 | expect(curMsg).toBeUndefined(); 12 | 13 | stream.addData(new Uint8Array([0])); 14 | expect(curMsg).toBeUndefined(); 15 | stream.addData(new Uint8Array([0])); 16 | expect(curMsg).toBeUndefined(); 17 | stream.addData(new Uint8Array([0])); 18 | expect(curMsg).toBeUndefined(); 19 | stream.addData(new Uint8Array([0])); 20 | expect(curMsg).toEqual(new Uint8Array()); 21 | }); 22 | 23 | it("decodes small messages", () => { 24 | const stream = new RosTcpMessageStream(); 25 | 26 | let curMsg: Uint8Array | undefined; 27 | stream.on("message", (msg) => (curMsg = msg)); 28 | 29 | stream.addData(new Uint8Array()); 30 | expect(curMsg).toBeUndefined(); 31 | 32 | stream.addData(new Uint8Array([1])); 33 | expect(curMsg).toBeUndefined(); 34 | stream.addData(new Uint8Array([0])); 35 | expect(curMsg).toBeUndefined(); 36 | stream.addData(new Uint8Array([0])); 37 | expect(curMsg).toBeUndefined(); 38 | stream.addData(new Uint8Array([0])); 39 | expect(curMsg).toBeUndefined(); 40 | stream.addData(new Uint8Array([42])); 41 | expect(curMsg).toEqual(new Uint8Array([42])); 42 | curMsg = undefined; 43 | 44 | stream.addData(new Uint8Array([2])); 45 | expect(curMsg).toBeUndefined(); 46 | stream.addData(new Uint8Array([0, 0])); 47 | expect(curMsg).toBeUndefined(); 48 | stream.addData(new Uint8Array([0, 43, 44])); 49 | expect(curMsg).toEqual(new Uint8Array([43, 44])); 50 | curMsg = undefined; 51 | 52 | stream.addData(new Uint8Array([3])); 53 | expect(curMsg).toBeUndefined(); 54 | stream.addData(new Uint8Array([])); 55 | expect(curMsg).toBeUndefined(); 56 | stream.addData(new Uint8Array([0])); 57 | expect(curMsg).toBeUndefined(); 58 | stream.addData(new Uint8Array([0, 0, 45])); 59 | stream.addData(new Uint8Array([46, 47, 1])); 60 | expect(curMsg).toEqual(new Uint8Array([45, 46, 47])); 61 | curMsg = undefined; 62 | 63 | stream.addData(new Uint8Array([0, 0, 0, 48, 0])); 64 | expect(curMsg).toEqual(new Uint8Array([48])); 65 | curMsg = undefined; 66 | 67 | stream.addData(new Uint8Array([0, 0, 0])); 68 | expect(curMsg).toEqual(new Uint8Array([])); 69 | }); 70 | 71 | it("fails on invalid stream data", () => { 72 | // 1000000001 === 0x3B9ACA01 73 | expect(() => 74 | new RosTcpMessageStream().addData(new Uint8Array([0x01, 0xca, 0x9a, 0x3b])), 75 | ).toThrow(); 76 | expect(() => 77 | new RosTcpMessageStream().addData(new Uint8Array([0x00, 0xca, 0x9a, 0x3b])), 78 | ).not.toThrow(); 79 | }); 80 | }); 81 | -------------------------------------------------------------------------------- /src/RosNode.test.ts: -------------------------------------------------------------------------------- 1 | import { HttpServerNodejs } from "@foxglove/xmlrpc/nodejs"; 2 | 3 | import { PublisherLink } from "./PublisherLink"; 4 | import { RosMaster } from "./RosMaster"; 5 | import { ParamUpdateArgs, RosNode } from "./RosNode"; 6 | import { TcpServerNode } from "./nodejs/TcpServerNode"; 7 | import { TcpSocketNode } from "./nodejs/TcpSocketNode"; 8 | 9 | describe("RosNode", () => { 10 | it("Publishes and subscribes to topics and parameters", async () => { 11 | const rosMaster = new RosMaster(new HttpServerNodejs()); 12 | await rosMaster.start("localhost"); 13 | const rosMasterUri = rosMaster.url() as string; 14 | expect(typeof rosMasterUri).toBe("string"); 15 | 16 | let errA: Error | undefined; 17 | let errB: Error | undefined; 18 | 19 | const nodeA = new RosNode({ 20 | name: "/nodeA", 21 | hostname: "localhost", 22 | pid: 1, 23 | rosMasterUri, 24 | httpServer: new HttpServerNodejs(), 25 | tcpSocketCreate: TcpSocketNode.Create, 26 | tcpServer: await TcpServerNode.Listen({ host: "0.0.0.0" }), 27 | // log: console, 28 | }); 29 | nodeA.on("error", (err) => (errA = err)); 30 | 31 | const nodeB = new RosNode({ 32 | name: "/nodeB", 33 | hostname: "localhost", 34 | pid: 2, 35 | rosMasterUri, 36 | httpServer: new HttpServerNodejs(), 37 | tcpSocketCreate: TcpSocketNode.Create, 38 | tcpServer: await TcpServerNode.Listen({ host: "0.0.0.0" }), 39 | // log: console, 40 | }); 41 | nodeB.on("error", (err) => (errB = err)); 42 | 43 | await nodeA.start(); 44 | 45 | const received = new Promise<[unknown, Uint8Array, PublisherLink]>((r) => { 46 | nodeA 47 | .subscribe({ topic: "/a", dataType: "std_msgs/Bool" }) 48 | .on("message", (msg, data, pub) => r([msg, data, pub])); 49 | }); 50 | 51 | await nodeB.start(); 52 | await nodeB.advertise({ 53 | topic: "/a", 54 | dataType: "std_msgs/Bool", 55 | messageDefinitionText: "bool data", 56 | latching: true, 57 | }); 58 | await nodeB.publish("/a", { data: true }); 59 | 60 | const [msg, data, pub] = await received; 61 | expect((msg as { data: boolean }).data).toEqual(true); 62 | expect(data).toHaveLength(1); 63 | expect(pub.connection.connected()).toEqual(true); 64 | expect(pub.connection.getTransportInfo().startsWith("TCPROS connection on port ")).toBe(true); 65 | expect(pub.connection.stats().bytesReceived).toEqual(143); 66 | expect(pub.connection.transportType()).toEqual("TCPROS"); 67 | expect(pub.connectionId).toEqual(0); 68 | expect(pub.subscription.md5sum).toEqual("*"); 69 | expect(pub.subscription.publishers().size).toEqual(1); 70 | expect(pub.subscription.receivedBytes()).toEqual(143); 71 | 72 | const initParamValue = await nodeB.subscribeParam("a"); 73 | expect(initParamValue).toBeUndefined(); 74 | const paramUpdated = new Promise((r) => { 75 | nodeB.on("paramUpdate", (args) => r(args)); 76 | }); 77 | 78 | await nodeA.setParameter("a", 42); 79 | 80 | const args = await paramUpdated; 81 | expect(args.callerId).toEqual("/nodeA"); 82 | expect(args.key).toEqual("a"); 83 | expect(args.value).toEqual(42); 84 | expect(args.prevValue).toBeUndefined(); 85 | 86 | nodeB.shutdown(); 87 | nodeA.shutdown(); 88 | await new Promise((r) => setTimeout(r, 100)); 89 | rosMaster.close(); 90 | 91 | expect(errA).toBeUndefined(); 92 | expect(errB).toBeUndefined(); 93 | }); 94 | }); 95 | -------------------------------------------------------------------------------- /src/nodejs/TcpSocketNode.ts: -------------------------------------------------------------------------------- 1 | import EventEmitter from "eventemitter3"; 2 | import net from "net"; 3 | 4 | import { TcpAddress, TcpSocket, TcpSocketEvents } from "../TcpTypes"; 5 | 6 | type MaybeHasFd = { 7 | _handle?: { 8 | fd?: number; 9 | }; 10 | }; 11 | 12 | export class TcpSocketNode extends EventEmitter implements TcpSocket { 13 | private _host: string; 14 | private _port: number; 15 | private _socket: net.Socket; 16 | 17 | constructor(host: string, port: number, socket: net.Socket) { 18 | super(); 19 | this._host = host; 20 | this._port = port; 21 | this._socket = socket; 22 | 23 | socket.on("connect", () => this.emit("connect")); 24 | socket.on("close", () => this.emit("close")); 25 | socket.on("data", (chunk) => this.emit("data", chunk)); 26 | socket.on("end", () => this.emit("end")); 27 | socket.on("timeout", () => this.emit("timeout")); 28 | socket.on("error", (err) => this.emit("error", err)); 29 | } 30 | 31 | async remoteAddress(): Promise { 32 | return { 33 | port: this._port, 34 | family: this._socket.remoteFamily, 35 | address: this._host, 36 | }; 37 | } 38 | 39 | async localAddress(): Promise { 40 | if (this._socket.destroyed) { 41 | return undefined; 42 | } 43 | const port = this._socket.localPort; 44 | const family = this._socket.remoteFamily; // There is no localFamily 45 | const address = this._socket.localAddress; 46 | return port != undefined && family != undefined && address != undefined 47 | ? { port, family, address } 48 | : undefined; 49 | } 50 | 51 | async fd(): Promise { 52 | // There is no public node.js API for retrieving the file descriptor for a 53 | // socket. This is the only way of retrieving it from pure JS, on platforms 54 | // where sockets have file descriptors. See 55 | // 56 | // eslint-disable-next-line no-underscore-dangle 57 | return (this._socket as unknown as MaybeHasFd)._handle?.fd; 58 | } 59 | 60 | async connected(): Promise { 61 | return !this._socket.destroyed && this._socket.localAddress != undefined; 62 | } 63 | 64 | async connect(): Promise { 65 | return await new Promise((resolve, reject) => { 66 | const KEEPALIVE_MS = 60 * 1000; 67 | 68 | this._socket.on("error", reject).connect(this._port, this._host, () => { 69 | this._socket.removeListener("error", reject); 70 | this._socket.setKeepAlive(true, KEEPALIVE_MS); 71 | resolve(); 72 | }); 73 | }); 74 | } 75 | 76 | async close(): Promise { 77 | this._socket.destroy(); 78 | } 79 | 80 | async write(data: Uint8Array): Promise { 81 | return await new Promise((resolve, reject) => { 82 | this._socket.write(data, (err) => { 83 | if (err != undefined) { 84 | reject(err); 85 | return; 86 | } 87 | resolve(); 88 | }); 89 | }); 90 | } 91 | 92 | // eslint-disable-next-line @foxglove/no-boolean-parameters 93 | async setNoDelay(noDelay?: boolean): Promise { 94 | this._socket.setNoDelay(noDelay); 95 | } 96 | 97 | static async Create( 98 | this: void, 99 | { host, port }: { host: string; port: number }, 100 | ): Promise { 101 | return new TcpSocketNode(host, port, new net.Socket()); 102 | } 103 | } 104 | -------------------------------------------------------------------------------- /src/TcpConnection.test.ts: -------------------------------------------------------------------------------- 1 | import net from "net"; 2 | import type { AddressInfo } from "net"; 3 | 4 | import { TcpConnection } from "./TcpConnection"; 5 | import { TcpSocket } from "./TcpTypes"; 6 | import { TcpSocketNode } from "./nodejs/TcpSocketNode"; 7 | 8 | //////////////////////////////////////////////////////////////////////////////// 9 | 10 | function hexToUint8Array(hex: string): Uint8Array { 11 | const match = hex.match(/[\da-f]{2}/gi); 12 | if (match == undefined) { 13 | return new Uint8Array(); 14 | } 15 | return new Uint8Array( 16 | match.map((h) => { 17 | return parseInt(h, 16); 18 | }), 19 | ); 20 | } 21 | 22 | const CLIENT_HEADER = new Map([ 23 | ["topic", "/turtle1/color_sensor"], 24 | ["md5sum", "*"], 25 | ["callerid", "/test"], 26 | ["type", "turtlesim/Color"], 27 | ["tcp_nodelay", "1"], 28 | ]); 29 | 30 | const HEADER = new Map([ 31 | ["callerid", "/turtlesim"], 32 | ["latching", "0"], 33 | ["md5sum", "353891e354491c51aabe32df673fb446"], 34 | ["message_definition", "uint8 r\nuint8 g\nuint8 b\n"], 35 | ["topic", "/turtle1/color_sensor"], 36 | ["type", "turtlesim/Color"], 37 | ]); 38 | const HEADER_DATA = hexToUint8Array( 39 | "1300000063616c6c657269643d2f747572746c6573696d0a0000006c61746368696e673d30270000006d643573756d3d33353338393165333534343931633531616162653332646636373366623434362b0000006d6573736167655f646566696e6974696f6e3d75696e743820720a75696e743820670a75696e743820620a1b000000746f7069633d2f747572746c65312f636f6c6f725f73656e736f7214000000747970653d747572746c6573696d2f436f6c6f72", 40 | ); 41 | 42 | describe("TcpConnection", () => { 43 | it("ParseHeader", () => { 44 | const header = TcpConnection.ParseHeader(HEADER_DATA); 45 | expect(header.size).toEqual(6); 46 | expect(header).toEqual(HEADER); 47 | }); 48 | 49 | it("SerializeHeader", () => { 50 | const data = TcpConnection.SerializeHeader(HEADER); 51 | expect(data).toEqual(HEADER_DATA); 52 | }); 53 | 54 | it("Connects and reads a parsed message", async () => { 55 | // Create the TCP listening socket 56 | const server = net.createServer((client) => { 57 | client.on("data", (fullData) => { 58 | const data = fullData.subarray(4); 59 | expect(data.byteLength).toEqual(102); 60 | expect(TcpConnection.ParseHeader(data)).toEqual(CLIENT_HEADER); 61 | 62 | client.write(new Uint8Array([0xb6, 0x00, 0x00, 0x00])); 63 | client.write(HEADER_DATA); 64 | client.write(new Uint8Array([0x03, 0x00, 0x00, 0x00])); 65 | client.write(new Uint8Array([0x45, 0x56, 0xff])); 66 | }); 67 | client.on("error", (err) => { 68 | throw err; 69 | }); 70 | }); 71 | await new Promise((resolve) => server.listen(undefined, undefined, undefined, resolve)); 72 | const port = (server.address() as AddressInfo).port; 73 | 74 | // Create the client socket 75 | const tcpSocketCreate = async (options: { host: string; port: number }): Promise => { 76 | return new TcpSocketNode(options.host, options.port, new net.Socket()); 77 | }; 78 | const socket = await tcpSocketCreate({ host: "localhost", port }); 79 | const connection = new TcpConnection(socket, "localhost", port, CLIENT_HEADER); 80 | const p = new Promise((resolve, reject) => { 81 | connection.on("message", (msg, data: Uint8Array) => { 82 | expect(data.byteLength).toEqual(3); 83 | resolve(msg); 84 | }); 85 | connection.on("error", reject); 86 | }); 87 | await socket.connect(); 88 | await expect(p).resolves.toEqual({ b: 255, g: 86, r: 69 }); 89 | 90 | connection.close(); 91 | await new Promise((resolve, reject) => 92 | server.close((err) => (err != undefined ? reject(err) : resolve())), 93 | ); 94 | }); 95 | }); 96 | -------------------------------------------------------------------------------- /src/RosMasterClient.test.ts: -------------------------------------------------------------------------------- 1 | /* eslint-disable @typescript-eslint/no-misused-promises */ 2 | /* eslint-disable jest/no-done-callback */ 3 | 4 | import http from "http"; 5 | import type { AddressInfo } from "net"; 6 | 7 | import { RosMasterClient } from "./RosMasterClient"; 8 | 9 | describe("RosMasterClient", () => { 10 | it("getPublishedTopics", (done) => { 11 | const server = http 12 | .createServer((_, res) => { 13 | res.writeHead(200, { "Content-Type": "text/xml" }); 14 | const data = ` 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 1 23 | 24 | 25 | current topics 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | /rosout 35 | 36 | 37 | rosgraph_msgs/Log 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | /turtle1/pose 47 | 48 | 49 | turtlesim/Pose 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | /turtle1/color_sensor 59 | 60 | 61 | turtlesim/Color 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | /rosout_agg 71 | 72 | 73 | rosgraph_msgs/Log 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | `; 87 | res.write(data); 88 | res.end(); 89 | }) 90 | .listen(undefined, "localhost", async () => { 91 | const port = (server.address() as AddressInfo).port; 92 | const client = new RosMasterClient(`http://localhost:${port}/`); 93 | const [status, msg, topics] = await client.getPublishedTopics("/test"); 94 | expect(status).toEqual(1); 95 | expect(msg).toEqual("current topics"); 96 | expect(topics).toEqual([ 97 | ["/rosout", "rosgraph_msgs/Log"], 98 | ["/turtle1/pose", "turtlesim/Pose"], 99 | ["/turtle1/color_sensor", "turtlesim/Color"], 100 | ["/rosout_agg", "rosgraph_msgs/Log"], 101 | ]); 102 | server.close(); 103 | done(); 104 | }); 105 | }); 106 | }); 107 | -------------------------------------------------------------------------------- /src/Publication.ts: -------------------------------------------------------------------------------- 1 | import { MessageDefinition } from "@foxglove/message-definition"; 2 | import { MessageWriter } from "@foxglove/rosmsg-serialization"; 3 | 4 | import { Client } from "./Client"; 5 | import { SubscriberLink } from "./SubscriberLink"; 6 | 7 | // [connectionId, bytesSent, messageDataSent, messagesSent, connected] 8 | type SubscriberStats = [number, number, number, number, 0]; 9 | 10 | // [connectionId, destinationCallerId, direction, transport, topicName, connected, connectionInfo] 11 | // e.g. [2, "/listener", "o", "TCPROS", "/chatter", true, "TCPROS connection on port 55878 to [127.0.0.1:44273 on socket 7]"] 12 | type SubscriberInfo = [number, string, "o", string, string, number, string]; 13 | 14 | export class Publication { 15 | readonly name: string; 16 | readonly md5sum: string; 17 | readonly dataType: string; 18 | readonly latching: boolean; 19 | readonly messageDefinition: MessageDefinition[]; 20 | readonly messageDefinitionText: string; 21 | readonly messageWriter: MessageWriter; 22 | private _latched = new Map(); 23 | private _subscribers = new Map(); 24 | 25 | constructor( 26 | name: string, 27 | md5sum: string, 28 | dataType: string, 29 | // eslint-disable-next-line @foxglove/no-boolean-parameters 30 | latching: boolean, 31 | messageDefinition: MessageDefinition[], 32 | messageDefinitionText: string, 33 | messageWriter: MessageWriter, 34 | ) { 35 | this.name = name; 36 | this.md5sum = md5sum; 37 | this.dataType = dataType; 38 | this.latching = latching; 39 | this.messageDefinition = messageDefinition; 40 | this.messageDefinitionText = messageDefinitionText; 41 | this.messageWriter = messageWriter; 42 | } 43 | 44 | subscribers(): Readonly> { 45 | return this._subscribers; 46 | } 47 | 48 | addSubscriber(connectionId: number, destinationCallerId: string, client: Client): void { 49 | const subscriber = new SubscriberLink(connectionId, destinationCallerId, client); 50 | this._subscribers.set(connectionId, subscriber); 51 | 52 | client.on("close", () => { 53 | this._subscribers.delete(connectionId); 54 | }); 55 | } 56 | 57 | async write(transportType: string, data: Uint8Array): Promise { 58 | if (this.latching) { 59 | this._latched.set(transportType, data); 60 | } 61 | 62 | const tasks: Promise[] = []; 63 | for (const sub of this._subscribers.values()) { 64 | if (sub.client.transportType() === transportType) { 65 | // A defensive copy of the data is needed here. The 66 | // source data array gets "detached". 67 | tasks.push(sub.client.write(new Uint8Array(data))); 68 | } 69 | } 70 | await Promise.allSettled(tasks); 71 | } 72 | 73 | close(): void { 74 | for (const sub of this._subscribers.values()) { 75 | sub.client.close(); 76 | } 77 | this._subscribers.clear(); 78 | } 79 | 80 | latchedMessage(transportType: string): Uint8Array | undefined { 81 | return this._latched.get(transportType); 82 | } 83 | 84 | getInfo(): SubscriberInfo[] { 85 | return Array.from(this._subscribers.values()).map((sub): SubscriberInfo => { 86 | return [ 87 | sub.connectionId, 88 | sub.destinationCallerId, 89 | "o", 90 | sub.client.transportType(), 91 | this.name, 92 | 1, 93 | sub.client.getTransportInfo(), 94 | ]; 95 | }); 96 | } 97 | 98 | getStats(): [string, SubscriberStats[]] { 99 | const subStats = Array.from(this._subscribers.values()).map((sub): SubscriberStats => { 100 | const stats = sub.client.stats(); 101 | return [sub.connectionId, stats.bytesSent, stats.bytesSent, stats.messagesSent, 0]; 102 | }); 103 | 104 | return [this.name, subStats]; 105 | } 106 | } 107 | -------------------------------------------------------------------------------- /src/mock/MockXmlRpc.ts: -------------------------------------------------------------------------------- 1 | import type { XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | import type { RosXmlRpcResponse } from "../XmlRpcTypes"; 4 | 5 | const TURTLESIM_SERVICES = new Set([ 6 | "/turtlesim/get_loggers", 7 | "/turtlesim/set_logger_level", 8 | "/clear", 9 | "/reset", 10 | "/spawn", 11 | "/kill", 12 | "/turtle1/set_pen", 13 | "/turtle1/teleport_relative", 14 | "/turtle1/teleport_absolute", 15 | "/rosout/get_loggers", 16 | "/rosout/set_logger_level", 17 | ]); 18 | 19 | export class XmlRpcClientMock { 20 | readonly serverUrl: string; 21 | 22 | constructor(serverUrl: string) { 23 | this.serverUrl = serverUrl; 24 | } 25 | 26 | async methodCall(method: string, args: XmlRpcValue[]): Promise { 27 | switch (method) { 28 | case "getPublishedTopics": 29 | return [ 30 | 1, 31 | "current topics", 32 | [ 33 | ["/rosout", "rosgraph_msgs/Log"], 34 | ["/turtle1/pose", "turtlesim/Pose"], 35 | ["/turtle1/color_sensor", "turtlesim/Color"], 36 | ["/rosout_agg", "rosgraph_msgs/Log"], 37 | ], 38 | ]; 39 | case "getSystemState": 40 | return [ 41 | 1, 42 | "current system state", 43 | [ 44 | [ 45 | ["/rosout", ["/turtlesim"]], 46 | ["/turtle1/pose", ["/turtlesim"]], 47 | ["/turtle1/color_sensor", ["/turtlesim"]], 48 | ["/rosout_agg", ["/rosout"]], 49 | ], 50 | [ 51 | ["/turtle1/cmd_vel", ["/turtlesim"]], 52 | ["/rosout", ["/rosout"]], 53 | ], 54 | [ 55 | ["/turtlesim/get_loggers", ["/turtlesim"]], 56 | ["/turtlesim/set_logger_level", ["/turtlesim"]], 57 | ["/clear", ["/turtlesim"]], 58 | ["/reset", ["/turtlesim"]], 59 | ["/spawn", ["/turtlesim"]], 60 | ["/kill", ["/turtlesim"]], 61 | ["/turtle1/set_pen", ["/turtlesim"]], 62 | ["/turtle1/teleport_relative", ["/turtlesim"]], 63 | ["/turtle1/teleport_absolute", ["/turtlesim"]], 64 | ["/rosout/get_loggers", ["/rosout"]], 65 | ["/rosout/set_logger_level", ["/rosout"]], 66 | ], 67 | ], 68 | ]; 69 | case "getTopicTypes": 70 | return [ 71 | 1, 72 | "current system state", // Not a typo 73 | [ 74 | ["/rosout", "rosgraph_msgs/Log"], 75 | ["/turtle1/cmd_vel", "geometry_msgs/Twist"], 76 | ["/turtle1/pose", "turtlesim/Pose"], 77 | ["/turtle1/color_sensor", "turtlesim/Color"], 78 | ["/rosout_agg", "rosgraph_msgs/Log"], 79 | ], 80 | ]; 81 | case "getUri": 82 | return [1, "", "http://localhost:11311/"]; 83 | case "lookupNode": { 84 | const nodeName = args[1]; 85 | if (nodeName === "/turtlesim") { 86 | return [1, "node api", "http://localhost:39211/"]; 87 | } 88 | return [-1, `unknown node [${nodeName}]`, ""]; 89 | } 90 | case "lookupService": { 91 | const serviceName = args[1]; 92 | if (TURTLESIM_SERVICES.has(serviceName as string)) { 93 | return [1, "rosrpc URI: [rosrpc://localhost:38017]", "rosrpc://localhost:38017"]; 94 | } 95 | return [-1, "no provider", ""]; 96 | } 97 | case "registerPublisher": 98 | case "registerService": 99 | return [-1, "not implemented", ""]; 100 | case "registerSubscriber": 101 | return [1, "", ["http://localhost:39211/"]]; 102 | case "unregisterPublisher": 103 | case "unregisterService": 104 | case "unregisterSubscriber": 105 | return [-1, "not implemented", ""]; 106 | default: 107 | return [-1, `unknown method [${method}]`, ""]; 108 | } 109 | } 110 | } 111 | -------------------------------------------------------------------------------- /src/Subscription.ts: -------------------------------------------------------------------------------- 1 | import { MessageDefinition } from "@foxglove/message-definition"; 2 | import { MessageReader } from "@foxglove/rosmsg-serialization"; 3 | import { EventEmitter } from "eventemitter3"; 4 | 5 | import { Connection } from "./Connection"; 6 | import { PublisherLink } from "./PublisherLink"; 7 | import { RosFollowerClient } from "./RosFollowerClient"; 8 | 9 | type PublisherStats = [ 10 | connectionId: number, 11 | bytesReceived: number, 12 | messagesReceived: number, 13 | estimatedDrops: number, 14 | connected: 0, 15 | ]; 16 | 17 | // e.g. [1, "http://host:54893/", "i", "TCPROS", "/chatter", 1, "TCPROS connection on port 59746 to [host:34318 on socket 11]"] 18 | type PublisherInfo = [ 19 | connectionId: number, 20 | publisherXmlRpcUri: string, 21 | direction: "i", 22 | transport: string, 23 | topicName: string, 24 | connected: number, 25 | connectionInfo: string, 26 | ]; 27 | 28 | type SubscriptionOpts = { 29 | name: string; 30 | md5sum: string; 31 | dataType: string; 32 | tcpNoDelay: boolean; 33 | }; 34 | 35 | export interface SubscriptionEvents { 36 | header: ( 37 | header: Map, 38 | msgDef: MessageDefinition[], 39 | msgReader: MessageReader, 40 | ) => void; 41 | message: (msg: unknown, data: Uint8Array, publisher: PublisherLink) => void; 42 | error: (err: Error) => void; 43 | } 44 | 45 | export class Subscription extends EventEmitter { 46 | readonly name: string; 47 | readonly md5sum: string; 48 | readonly dataType: string; 49 | readonly tcpNoDelay: boolean; 50 | private _publishers = new Map(); 51 | 52 | constructor({ name, md5sum, dataType, tcpNoDelay }: SubscriptionOpts) { 53 | super(); 54 | this.name = name; 55 | this.md5sum = md5sum; 56 | this.dataType = dataType; 57 | this.tcpNoDelay = tcpNoDelay; 58 | } 59 | 60 | close(): void { 61 | this.removeAllListeners(); 62 | for (const pub of this._publishers.values()) { 63 | pub.connection.close(); 64 | } 65 | this._publishers.clear(); 66 | } 67 | 68 | publishers(): Readonly> { 69 | return this._publishers; 70 | } 71 | 72 | addPublisher( 73 | connectionId: number, 74 | rosFollowerClient: RosFollowerClient, 75 | connection: Connection, 76 | ): void { 77 | const publisher = new PublisherLink(connectionId, this, rosFollowerClient, connection); 78 | this._publishers.set(connectionId, publisher); 79 | 80 | connection.on("header", (header, def, reader) => this.emit("header", header, def, reader)); 81 | connection.on("message", (msg, data) => this.emit("message", msg, data, publisher)); 82 | connection.on("error", (err) => this.emit("error", err)); 83 | } 84 | 85 | removePublisher(connectionId: number): boolean { 86 | this._publishers.get(connectionId)?.connection.close(); 87 | return this._publishers.delete(connectionId); 88 | } 89 | 90 | getInfo(): PublisherInfo[] { 91 | return Array.from(this._publishers.values()).map((pub): PublisherInfo => { 92 | return [ 93 | pub.connectionId, 94 | pub.publisherXmlRpcUrl().toString(), 95 | "i", 96 | pub.connection.transportType(), 97 | this.name, 98 | 1, 99 | pub.connection.getTransportInfo(), 100 | ]; 101 | }); 102 | } 103 | 104 | getStats(): [string, PublisherStats[]] { 105 | const pubStats = Array.from(this._publishers.values()).map((pub): PublisherStats => { 106 | const stats = pub.connection.stats(); 107 | return [pub.connectionId, stats.bytesReceived, stats.messagesReceived, stats.dropEstimate, 0]; 108 | }); 109 | return [this.name, pubStats]; 110 | } 111 | 112 | receivedBytes(): number { 113 | let bytes = 0; 114 | for (const pub of this._publishers.values()) { 115 | bytes += pub.connection.stats().bytesReceived; 116 | } 117 | return bytes; 118 | } 119 | } 120 | -------------------------------------------------------------------------------- /src/TcpPublisher.ts: -------------------------------------------------------------------------------- 1 | import { EventEmitter } from "eventemitter3"; 2 | 3 | import { Client } from "./Client"; 4 | import { LoggerService } from "./LoggerService"; 5 | import { Publication } from "./Publication"; 6 | import { Publisher } from "./Publisher"; 7 | import { PublicationLookup, TcpClient } from "./TcpClient"; 8 | import type { TcpAddress, TcpServer, TcpSocket } from "./TcpTypes"; 9 | 10 | type TcpPublisherOpts = { 11 | server: TcpServer; 12 | nodeName: string; 13 | getConnectionId: () => number; 14 | getPublication: PublicationLookup; 15 | log?: LoggerService; 16 | }; 17 | 18 | interface TcpPublisherEvents { 19 | connection: ( 20 | topic: string, 21 | connectionId: number, 22 | destinationCallerId: string, 23 | client: Client, 24 | ) => void; 25 | error: (err: Error) => void; 26 | } 27 | 28 | // Implements publishing support for the TCPROS transport. The actual TCP server 29 | // is implemented in the passed in `server` (TcpServer). A `RosNode` instance 30 | // uses a single `TcpPublisher` instance for all published topics, each incoming 31 | // TCP connection sends a connection header that specifies which topic that 32 | // connection is subscribing to. 33 | export class TcpPublisher extends EventEmitter implements Publisher { 34 | private _server: TcpServer; 35 | private _nodeName: string; 36 | private _getConnectionId: () => number; 37 | private _getPublication: PublicationLookup; 38 | private _pendingClients = new Map(); 39 | private _shutdown = false; 40 | private _log?: LoggerService; 41 | 42 | constructor({ server, nodeName, getConnectionId, getPublication, log }: TcpPublisherOpts) { 43 | super(); 44 | this._server = server; 45 | this._nodeName = nodeName; 46 | this._getConnectionId = getConnectionId; 47 | this._getPublication = getPublication; 48 | this._log = log; 49 | 50 | // eslint-disable-next-line @typescript-eslint/no-misused-promises 51 | server.on("connection", this._handleConnection); 52 | server.on("close", this._handleClose); 53 | server.on("error", this._handleError); 54 | } 55 | 56 | async address(): Promise { 57 | return await this._server.address(); 58 | } 59 | 60 | async publish(publication: Publication, message: unknown): Promise { 61 | const msgSize = publication.messageWriter.calculateByteSize(message); 62 | const dataSize = 4 + msgSize; 63 | const buffer = new ArrayBuffer(dataSize); 64 | 65 | // Write the 4-byte size integer 66 | new DataView(buffer, 0, 4).setUint32(0, msgSize, true); 67 | 68 | // Write the serialized message data 69 | const msgData = new Uint8Array(buffer, 4, dataSize - 4); 70 | publication.messageWriter.writeMessage(message, msgData); 71 | 72 | const data = new Uint8Array(buffer, 0, dataSize); 73 | return await publication.write(this.transportType(), data); 74 | } 75 | 76 | transportType(): string { 77 | return "TCPROS"; 78 | } 79 | 80 | listening(): boolean { 81 | return !this._shutdown; 82 | } 83 | 84 | close(): void { 85 | this._log?.debug?.(`stopping tcp publisher for ${this._nodeName}`); 86 | 87 | this._shutdown = true; 88 | this.removeAllListeners(); 89 | this._server.close(); 90 | 91 | for (const client of this._pendingClients.values()) { 92 | client.removeAllListeners(); 93 | client.close(); 94 | } 95 | this._pendingClients.clear(); 96 | } 97 | 98 | // TcpServer handlers //////////////////////////////////////////////////////// 99 | 100 | private _handleConnection = async (socket: TcpSocket): Promise => { 101 | const noOp = () => { 102 | // no-op 103 | }; 104 | 105 | if (this._shutdown) { 106 | socket.close().catch(noOp); 107 | return; 108 | } 109 | 110 | // TcpClient must be instantiated before any async calls since it registers event handlers 111 | // that may not be setup in time otherwise 112 | const client = new TcpClient({ 113 | socket, 114 | nodeName: this._nodeName, 115 | getPublication: this._getPublication, 116 | log: this._log, 117 | }); 118 | 119 | const connectionId = this._getConnectionId(); 120 | this._pendingClients.set(connectionId, client); 121 | 122 | client.on("subscribe", (topic, destinationCallerId) => { 123 | this._pendingClients.delete(connectionId); 124 | if (!this._shutdown) { 125 | this.emit("connection", topic, connectionId, destinationCallerId, client); 126 | } 127 | }); 128 | client.on("error", (err) => { 129 | if (!this._shutdown) { 130 | this._log?.warn?.(`tcp client ${client.toString()} error: ${err}`); 131 | this.emit("error", new Error(`TCP client ${client.toString()} error: ${err}`)); 132 | } 133 | }); 134 | }; 135 | 136 | private _handleClose = (): void => { 137 | if (!this._shutdown) { 138 | this._log?.warn?.(`tcp server closed unexpectedly. shutting down tcp publisher`); 139 | this.emit("error", new Error("TCP publisher closed unexpectedly")); 140 | this._shutdown = true; 141 | } 142 | }; 143 | 144 | private _handleError = (err: Error): void => { 145 | if (!this._shutdown) { 146 | this._log?.warn?.(`tcp publisher error: ${err}`); 147 | this.emit("error", err); 148 | } 149 | }; 150 | } 151 | -------------------------------------------------------------------------------- /src/RosFollower.ts: -------------------------------------------------------------------------------- 1 | import { HttpServer, HttpRequest, XmlRpcServer, XmlRpcValue } from "@foxglove/xmlrpc"; 2 | import { EventEmitter } from "eventemitter3"; 3 | import ipaddr from "ipaddr.js"; 4 | 5 | import { RosNode } from "./RosNode"; 6 | import { RosXmlRpcResponse } from "./XmlRpcTypes"; 7 | 8 | function CheckArguments(args: XmlRpcValue[], expected: string[]): Error | undefined { 9 | if (args.length !== expected.length) { 10 | return new Error(`Expected ${expected.length} arguments, got ${args.length}`); 11 | } 12 | 13 | for (let i = 0; i < args.length; i++) { 14 | if (expected[i] !== "*" && typeof args[i] !== expected[i]) { 15 | return new Error(`Expected "${expected[i]}" for arg ${i}, got "${typeof args[i]}"`); 16 | } 17 | } 18 | 19 | return undefined; 20 | } 21 | 22 | function TcpRequested(protocols: XmlRpcValue[]): boolean { 23 | for (const proto of protocols) { 24 | if (Array.isArray(proto) && proto.length > 0) { 25 | if (proto[0] === "TCPROS") { 26 | return true; 27 | } 28 | } 29 | } 30 | return false; 31 | } 32 | 33 | export interface RosFollowerEvents { 34 | paramUpdate: (paramKey: string, paramValue: XmlRpcValue, callerId: string) => void; 35 | publisherUpdate: (topic: string, publishers: string[], callerId: string) => void; 36 | } 37 | 38 | export class RosFollower extends EventEmitter { 39 | private _rosNode: RosNode; 40 | private _server: XmlRpcServer; 41 | private _url?: string; 42 | 43 | constructor(rosNode: RosNode, httpServer: HttpServer) { 44 | super(); 45 | this._rosNode = rosNode; 46 | this._server = new XmlRpcServer(httpServer); 47 | } 48 | 49 | async start(hostname: string, port?: number): Promise { 50 | await this._server.listen(port, undefined, 10); 51 | this._url = `http://${hostname}:${this._server.port()}/`; 52 | 53 | this._server.setHandler("getBusStats", this.getBusStats); 54 | this._server.setHandler("getBusInfo", this.getBusInfo); 55 | this._server.setHandler("shutdown", this.shutdown); 56 | this._server.setHandler("getPid", this.getPid); 57 | this._server.setHandler("getSubscriptions", this.getSubscriptions); 58 | this._server.setHandler("getPublications", this.getPublications); 59 | this._server.setHandler("paramUpdate", this.paramUpdate); 60 | this._server.setHandler("publisherUpdate", this.publisherUpdate); 61 | this._server.setHandler("requestTopic", this.requestTopic); 62 | } 63 | 64 | close(): void { 65 | this._server.close(); 66 | } 67 | 68 | url(): string | undefined { 69 | return this._url; 70 | } 71 | 72 | getBusStats = async (_: string, args: XmlRpcValue[]): Promise => { 73 | const err = CheckArguments(args, ["string"]); 74 | if (err != null) { 75 | throw err; 76 | } 77 | 78 | const publications = this._rosNode.publications.values(); 79 | const subscriptions = this._rosNode.subscriptions.values(); 80 | 81 | const publishStats: XmlRpcValue[] = Array.from(publications, (pub, __) => pub.getStats()); 82 | const subscribeStats: XmlRpcValue[] = Array.from(subscriptions, (sub, __) => sub.getStats()); 83 | const serviceStats: XmlRpcValue[] = []; 84 | 85 | return [1, "", [publishStats, subscribeStats, serviceStats]]; 86 | }; 87 | 88 | getBusInfo = async (_: string, args: XmlRpcValue[]): Promise => { 89 | const err = CheckArguments(args, ["string"]); 90 | if (err != null) { 91 | throw err; 92 | } 93 | 94 | return [1, "", ""]; 95 | }; 96 | 97 | shutdown = async (_: string, args: XmlRpcValue[]): Promise => { 98 | if (args.length !== 1 && args.length !== 2) { 99 | throw new Error(`Expected 1-2 arguments, got ${args.length}`); 100 | } 101 | 102 | for (let i = 0; i < args.length; i++) { 103 | if (typeof args[i] !== "string") { 104 | throw new Error(`Expected "string" for arg ${i}, got "${typeof args[i]}"`); 105 | } 106 | } 107 | 108 | const msg = args[1] as string | undefined; 109 | this._rosNode.shutdown(msg); 110 | 111 | return [1, "", 0]; 112 | }; 113 | 114 | getPid = async (_: string, args: XmlRpcValue[]): Promise => { 115 | const err = CheckArguments(args, ["string"]); 116 | if (err != null) { 117 | throw err; 118 | } 119 | 120 | return [1, "", this._rosNode.pid]; 121 | }; 122 | 123 | getSubscriptions = async (_: string, args: XmlRpcValue[]): Promise => { 124 | const err = CheckArguments(args, ["string"]); 125 | if (err != null) { 126 | throw err; 127 | } 128 | 129 | const subs: [string, string][] = []; 130 | this._rosNode.subscriptions.forEach((sub) => subs.push([sub.name, sub.dataType])); 131 | return [1, "subscriptions", subs]; 132 | }; 133 | 134 | getPublications = async (_: string, args: XmlRpcValue[]): Promise => { 135 | const err = CheckArguments(args, ["string"]); 136 | if (err != null) { 137 | throw err; 138 | } 139 | 140 | const pubs: [string, string][] = []; 141 | this._rosNode.publications.forEach((pub) => pubs.push([pub.name, pub.dataType])); 142 | return [1, "publications", pubs]; 143 | }; 144 | 145 | paramUpdate = async (_: string, args: XmlRpcValue[]): Promise => { 146 | const err = CheckArguments(args, ["string", "string", "*"]); 147 | if (err != null) { 148 | throw err; 149 | } 150 | 151 | const [callerId, paramKey, paramValue] = args as [string, string, XmlRpcValue]; 152 | 153 | // Normalize the parameter key since rosparam server may append "/" 154 | const normalizedKey = paramKey.endsWith("/") ? paramKey.slice(0, -1) : paramKey; 155 | 156 | this.emit("paramUpdate", normalizedKey, paramValue, callerId); 157 | 158 | return [1, "", 0]; 159 | }; 160 | 161 | publisherUpdate = async (_: string, args: XmlRpcValue[]): Promise => { 162 | const err = CheckArguments(args, ["string", "string", "*"]); 163 | if (err != null) { 164 | throw err; 165 | } 166 | 167 | const [callerId, topic, publishers] = args as [string, string, string[]]; 168 | if (!Array.isArray(publishers)) { 169 | throw new Error(`invalid publishers list`); 170 | } 171 | this.emit("publisherUpdate", topic, publishers, callerId); 172 | 173 | return [1, "", 0]; 174 | }; 175 | 176 | requestTopic = async ( 177 | _: string, 178 | args: XmlRpcValue[], 179 | req?: HttpRequest, 180 | ): Promise => { 181 | const err = CheckArguments(args, ["string", "string", "*"]); 182 | if (err != null) { 183 | throw err; 184 | } 185 | 186 | const topic = args[1] as string; 187 | if (!this._rosNode.publications.has(topic)) { 188 | return [0, `topic "${topic} is not advertised by node ${this._rosNode.name}"`, []]; 189 | } 190 | 191 | const protocols = args[2]; 192 | if (!Array.isArray(protocols) || !TcpRequested(protocols)) { 193 | return [0, "unsupported protocol", []]; 194 | } 195 | 196 | const addr = await this._rosNode.tcpServerAddress(); 197 | if (addr == undefined) { 198 | return [0, "cannot receive incoming connections", []]; 199 | } 200 | 201 | // ROS subscriber clients use the address and port response arguments to determine where to 202 | // establish a connection to receive messages. ROS clients may be on the local machine or on 203 | // remote hosts. To better support subscribers on local or remote hosts, we attempt to use the 204 | // socket localAddress of the xmlrpc request if it present. Since the xmlrpc server and tcp 205 | // socket publishers are launched within the same node, echoing the localAddress back as the 206 | // tpcros destination address increases the chance the client will be able to establish a 207 | // connection to the publishing node since it has already made a successful xmlrpc request to 208 | // the same address. 209 | // 210 | // Note: We still use `addr.port` because we need the _port_ of the TCP server not the HTTP 211 | // xmlrpc server. 212 | const socketLocalAddress = ipaddr.process(req?.socket?.localAddress ?? addr.address); 213 | return [1, "", ["TCPROS", socketLocalAddress.toString(), addr.port]]; 214 | }; 215 | } 216 | -------------------------------------------------------------------------------- /src/TcpClient.ts: -------------------------------------------------------------------------------- 1 | import EventEmitter from "eventemitter3"; 2 | 3 | import { Client, ClientStats } from "./Client"; 4 | import { LoggerService } from "./LoggerService"; 5 | import { Publication } from "./Publication"; 6 | import { RosTcpMessageStream } from "./RosTcpMessageStream"; 7 | import { TcpConnection } from "./TcpConnection"; 8 | import { TcpSocket } from "./TcpTypes"; 9 | 10 | export type PublicationLookup = (topic: string) => Publication | undefined; 11 | 12 | type TcpClientOpts = { 13 | socket: TcpSocket; 14 | nodeName: string; 15 | getPublication: PublicationLookup; 16 | log?: LoggerService; 17 | }; 18 | 19 | export interface TcpClientEvents { 20 | close: () => void; 21 | subscribe: (topic: string, destinationCallerId: string) => void; 22 | error: (err: Error) => void; 23 | } 24 | 25 | export class TcpClient extends EventEmitter implements Client { 26 | private _socket: TcpSocket; 27 | private _address?: string; 28 | private _port?: number; 29 | private _transportInfo: string; 30 | private _nodeName: string; 31 | private _connected = true; 32 | private _receivedHeader = false; 33 | private _stats: ClientStats = { bytesSent: 0, bytesReceived: 0, messagesSent: 0 }; 34 | private _getPublication: PublicationLookup; 35 | private _log?: LoggerService; 36 | private _transformer: RosTcpMessageStream; 37 | 38 | constructor({ socket, nodeName, getPublication, log }: TcpClientOpts) { 39 | super(); 40 | this._socket = socket; 41 | this._nodeName = nodeName; 42 | this._getPublication = getPublication; 43 | this._log = log; 44 | this._transformer = new RosTcpMessageStream(); 45 | this._transportInfo = `TCPROS establishing connection`; 46 | 47 | socket.on("close", this._handleClose); 48 | socket.on("error", this._handleError); 49 | socket.on("data", this._handleData); 50 | 51 | // eslint-disable-next-line @typescript-eslint/no-misused-promises 52 | this._transformer.on("message", this._handleMessage); 53 | 54 | void this._updateTransportInfo(); 55 | 56 | // Wait for the client to send the initial connection header 57 | } 58 | 59 | transportType(): string { 60 | return "TCPROS"; 61 | } 62 | 63 | connected(): boolean { 64 | return this._connected; 65 | } 66 | 67 | stats(): ClientStats { 68 | return this._stats; 69 | } 70 | 71 | async write(data: Uint8Array): Promise { 72 | try { 73 | await this._socket.write(data); 74 | this._stats.messagesSent++; 75 | this._stats.bytesSent += data.length; 76 | } catch (err) { 77 | this._log?.warn?.(`failed to write ${data.length} bytes to ${this.toString()}: ${err}`); 78 | } 79 | } 80 | 81 | close(): void { 82 | this._socket 83 | .close() 84 | .catch((err) => this._log?.warn?.(`error closing client socket ${this.toString()}: ${err}`)); 85 | } 86 | 87 | getTransportInfo(): string { 88 | return this._transportInfo; 89 | } 90 | 91 | override toString(): string { 92 | return TcpConnection.Uri(this._address ?? "", this._port ?? 0); 93 | } 94 | 95 | private _updateTransportInfo = async (): Promise => { 96 | let fd = -1; 97 | try { 98 | fd = (await this._socket.fd()) ?? -1; 99 | const localPort = (await this._socket.localAddress())?.port ?? -1; 100 | const addr = await this._socket.remoteAddress(); 101 | if (addr == undefined) { 102 | throw new Error(`Socket ${fd} on local port ${localPort} could not resolve remoteAddress`); 103 | } 104 | 105 | const { address, port } = addr; 106 | const host = address.includes(":") ? `[${address}]` : address; 107 | this._address = address; 108 | this._port = port; 109 | this._transportInfo = `TCPROS connection on port ${localPort} to [${host}:${port} on socket ${fd}]`; 110 | } catch (err) { 111 | this._transportInfo = `TCPROS not connected [socket ${fd}]`; 112 | this._log?.warn?.(`Cannot resolve address for tcp connection: ${err}`); 113 | this.emit("error", new Error(`Cannot resolve address for tcp connection: ${err}`)); 114 | } 115 | }; 116 | 117 | private async _writeHeader(header: Map): Promise { 118 | const data = TcpConnection.SerializeHeader(header); 119 | 120 | // Write the serialized header payload 121 | const buffer = new ArrayBuffer(4 + data.length); 122 | const payload = new Uint8Array(buffer); 123 | const view = new DataView(buffer); 124 | view.setUint32(0, data.length, true); 125 | payload.set(data, 4); 126 | 127 | try { 128 | await this._socket.write(payload); 129 | this._stats.bytesSent += payload.length; 130 | } catch (err) { 131 | this._log?.warn?.( 132 | `failed to write ${data.length + 4} byte header to ${this.toString()}: ${err}`, 133 | ); 134 | } 135 | } 136 | 137 | private _handleClose = () => { 138 | this._connected = false; 139 | this.emit("close"); 140 | }; 141 | 142 | private _handleError = (err: Error) => { 143 | this._log?.warn?.(`tcp client ${this.toString()} error: ${err}`); 144 | this.emit("error", err); 145 | }; 146 | 147 | private _handleData = (chunk: Uint8Array) => { 148 | try { 149 | this._transformer.addData(chunk); 150 | } catch (unk) { 151 | const err = unk instanceof Error ? unk : new Error(unk as string); 152 | this._log?.warn?.( 153 | `failed to decode ${chunk.length} byte chunk from tcp client ${this.toString()}: ${err}`, 154 | ); 155 | // Close the socket, the stream is now corrupt 156 | void this._socket.close(); 157 | this.emit("error", err); 158 | } 159 | }; 160 | 161 | private _handleMessage = async (msgData: Uint8Array) => { 162 | // Check if we have already received the connection header from this client 163 | if (this._receivedHeader) { 164 | this._log?.warn?.(`tcp client ${this.toString()} sent ${msgData.length} bytes after header`); 165 | this._stats.bytesReceived += msgData.byteLength; 166 | return; 167 | } 168 | 169 | const header = TcpConnection.ParseHeader(msgData); 170 | const topic = header.get("topic"); 171 | const destinationCallerId = header.get("callerid"); 172 | const dataType = header.get("type"); 173 | const md5sum = header.get("md5sum") ?? "*"; 174 | const tcpNoDelay = header.get("tcp_nodelay") === "1"; 175 | 176 | this._receivedHeader = true; 177 | 178 | void this._socket.setNoDelay(tcpNoDelay); 179 | 180 | if (topic == undefined || dataType == undefined || destinationCallerId == undefined) { 181 | this._log?.warn?.( 182 | `tcp client ${this.toString()} sent incomplete header. topic="${topic}", type="${dataType}", callerid="${destinationCallerId}"`, 183 | ); 184 | return this.close(); 185 | } 186 | 187 | // Check if we are publishing this topic 188 | const pub = this._getPublication(topic); 189 | if (pub == undefined) { 190 | this._log?.warn?.( 191 | `tcp client ${this.toString()} attempted to subscribe to unadvertised topic ${topic}`, 192 | ); 193 | return this.close(); 194 | } 195 | 196 | this._stats.bytesReceived += msgData.byteLength; 197 | 198 | // Check the dataType matches 199 | if (dataType !== "*" && pub.dataType !== dataType) { 200 | this._log?.warn?.( 201 | `tcp client ${this.toString()} attempted to subscribe to topic ${topic} with type "${dataType}", expected "${ 202 | pub.dataType 203 | }"`, 204 | ); 205 | return this.close(); 206 | } 207 | 208 | // Check the md5sum matches 209 | if (md5sum !== "*" && pub.md5sum !== md5sum) { 210 | this._log?.warn?.( 211 | `tcp client ${this.toString()} attempted to subscribe to topic ${topic} with md5sum "${md5sum}", expected "${ 212 | pub.md5sum 213 | }"`, 214 | ); 215 | return this.close(); 216 | } 217 | 218 | // Write the response header 219 | void this._writeHeader( 220 | new Map([ 221 | ["callerid", this._nodeName], 222 | ["latching", pub.latching ? "1" : "0"], 223 | ["md5sum", pub.md5sum], 224 | ["message_definition", pub.messageDefinitionText], 225 | ["topic", pub.name], 226 | ["type", pub.dataType], 227 | ]), 228 | ); 229 | 230 | // Immediately send the last published message if latching is enabled 231 | const latched = pub.latchedMessage(this.transportType()); 232 | if (latched != undefined) { 233 | void this.write(latched); 234 | } 235 | 236 | this.emit("subscribe", topic, destinationCallerId); 237 | }; 238 | } 239 | -------------------------------------------------------------------------------- /src/TcpConnection.ts: -------------------------------------------------------------------------------- 1 | import { MessageDefinition } from "@foxglove/message-definition"; 2 | import { parse as parseMessageDefinition } from "@foxglove/rosmsg"; 3 | import { MessageReader } from "@foxglove/rosmsg-serialization"; 4 | import { EventEmitter } from "eventemitter3"; 5 | 6 | import { Connection, ConnectionStats } from "./Connection"; 7 | import { LoggerService } from "./LoggerService"; 8 | import { RosTcpMessageStream } from "./RosTcpMessageStream"; 9 | import { TcpAddress, TcpSocket } from "./TcpTypes"; 10 | import { backoff } from "./backoff"; 11 | 12 | export interface TcpConnectionEvents { 13 | header: ( 14 | header: Map, 15 | messageDefinition: MessageDefinition[], 16 | messageReader: MessageReader, 17 | ) => void; 18 | message: (msg: unknown, msgData: Uint8Array) => void; 19 | error: (err: Error) => void; 20 | } 21 | 22 | // Implements a subscriber for the TCPROS transport. The actual TCP transport is 23 | // implemented in the passed in `socket` (TcpSocket). A transform stream is used 24 | // internally for parsing the TCPROS message format (4 byte length followed by 25 | // message payload) so "message" events represent one full message each without 26 | // the length prefix. A transform class that meets this requirements is 27 | // implemented in `RosTcpMessageStream`. 28 | export class TcpConnection extends EventEmitter implements Connection { 29 | retries = 0; 30 | 31 | private _socket: TcpSocket; 32 | private _address: string; 33 | private _port: number; 34 | private _connected = false; 35 | private _shutdown = false; 36 | private _transportInfo = "TCPROS not connected [socket -1]"; 37 | private _readingHeader = true; 38 | private _requestHeader: Map; 39 | private _header = new Map(); 40 | private _stats = { 41 | bytesSent: 0, 42 | bytesReceived: 0, 43 | messagesSent: 0, 44 | messagesReceived: 0, 45 | dropEstimate: -1, 46 | }; 47 | private _transformer = new RosTcpMessageStream(); 48 | private _msgDefinition: MessageDefinition[] = []; 49 | private _msgReader: MessageReader | undefined; 50 | private _log?: LoggerService; 51 | 52 | constructor( 53 | socket: TcpSocket, 54 | address: string, 55 | port: number, 56 | requestHeader: Map, 57 | log?: LoggerService, 58 | ) { 59 | super(); 60 | this._socket = socket; 61 | this._address = address; 62 | this._port = port; 63 | this._requestHeader = requestHeader; 64 | this._log = log; 65 | 66 | // eslint-disable-next-line @typescript-eslint/no-misused-promises 67 | socket.on("connect", this._handleConnect); 68 | socket.on("close", this._handleClose); 69 | socket.on("error", this._handleError); 70 | socket.on("data", this._handleData); 71 | 72 | this._transformer.on("message", this._handleMessage); 73 | } 74 | 75 | transportType(): string { 76 | return "TCPROS"; 77 | } 78 | 79 | async remoteAddress(): Promise { 80 | return await this._socket.remoteAddress(); 81 | } 82 | 83 | async connect(): Promise { 84 | if (this._shutdown) { 85 | return; 86 | } 87 | 88 | this._log?.debug?.(`connecting to ${this.toString()} (attempt ${this.retries})`); 89 | 90 | try { 91 | await this._socket.connect(); 92 | this._log?.debug?.(`connected to ${this.toString()}`); 93 | } catch (err) { 94 | this._log?.warn?.(`${this.toString()} connection failed: ${err}`); 95 | // _handleClose() will be called, triggering a reconnect attempt 96 | } 97 | } 98 | 99 | private _retryConnection(): void { 100 | if (!this._shutdown) { 101 | backoff(++this.retries) 102 | // eslint-disable-next-line @typescript-eslint/promise-function-async 103 | .then(() => this.connect()) 104 | .catch((err) => { 105 | // This should never be called, this.connect() is not expected to throw 106 | this._log?.warn?.(`${this.toString()} unexpected retry failure: ${err}`); 107 | }); 108 | } 109 | } 110 | 111 | connected(): boolean { 112 | return this._connected; 113 | } 114 | 115 | header(): Map { 116 | return new Map(this._header); 117 | } 118 | 119 | stats(): ConnectionStats { 120 | return this._stats; 121 | } 122 | 123 | messageDefinition(): MessageDefinition[] { 124 | return this._msgDefinition; 125 | } 126 | 127 | messageReader(): MessageReader | undefined { 128 | return this._msgReader; 129 | } 130 | 131 | close(): void { 132 | this._log?.debug?.(`closing connection to ${this.toString()}`); 133 | 134 | this._shutdown = true; 135 | this._connected = false; 136 | this.removeAllListeners(); 137 | this._socket.close().catch((err) => { 138 | this._log?.warn?.(`${this.toString()} close failed: ${err}`); 139 | }); 140 | } 141 | 142 | async writeHeader(): Promise { 143 | const serializedHeader = TcpConnection.SerializeHeader(this._requestHeader); 144 | const totalLen = 4 + serializedHeader.byteLength; 145 | this._stats.bytesSent += totalLen; 146 | 147 | const data = new Uint8Array(totalLen); 148 | 149 | // Write the 4-byte length 150 | const view = new DataView(data.buffer, data.byteOffset, data.byteLength); 151 | view.setUint32(0, serializedHeader.byteLength, true); 152 | 153 | // Copy the serialized header into the final buffer 154 | data.set(serializedHeader, 4); 155 | 156 | // Write the length and serialized header payload 157 | return await this._socket.write(data); 158 | } 159 | 160 | // e.g. "TCPROS connection on port 59746 to [host:34318 on socket 11]" 161 | getTransportInfo(): string { 162 | return this._transportInfo; 163 | } 164 | 165 | override toString(): string { 166 | return TcpConnection.Uri(this._address, this._port); 167 | } 168 | 169 | private _getTransportInfo = async (): Promise => { 170 | const localPort = (await this._socket.localAddress())?.port ?? -1; 171 | const addr = await this._socket.remoteAddress(); 172 | const fd = (await this._socket.fd()) ?? -1; 173 | if (addr != null) { 174 | const { address, port } = addr; 175 | const host = address.includes(":") ? `[${address}]` : address; 176 | return `TCPROS connection on port ${localPort} to [${host}:${port} on socket ${fd}]`; 177 | } 178 | return `TCPROS not connected [socket ${fd}]`; 179 | }; 180 | 181 | private _handleConnect = async (): Promise => { 182 | if (this._shutdown) { 183 | this.close(); 184 | return; 185 | } 186 | 187 | this._connected = true; 188 | this.retries = 0; 189 | this._transportInfo = await this._getTransportInfo(); 190 | 191 | try { 192 | // Write the initial request header. This prompts the publisher to respond 193 | // with its own header then start streaming messages 194 | await this.writeHeader(); 195 | } catch (err) { 196 | this._log?.warn?.(`${this.toString()} failed to write header. reconnecting: ${err}`); 197 | this.emit("error", new Error(`Header write failed: ${err}`)); 198 | this._retryConnection(); 199 | } 200 | }; 201 | 202 | private _handleClose = (): void => { 203 | this._connected = false; 204 | if (!this._shutdown) { 205 | this._log?.warn?.(`${this.toString()} closed unexpectedly. reconnecting`); 206 | this.emit("error", new Error("Connection closed unexpectedly")); 207 | this._retryConnection(); 208 | } 209 | }; 210 | 211 | private _handleError = (err: Error): void => { 212 | if (!this._shutdown) { 213 | this._log?.warn?.(`${this.toString()} error: ${err}`); 214 | this.emit("error", err); 215 | } 216 | }; 217 | 218 | private _handleData = (chunk: Uint8Array): void => { 219 | if (this._shutdown) { 220 | return; 221 | } 222 | 223 | try { 224 | this._transformer.addData(chunk); 225 | } catch (unk) { 226 | const err = unk instanceof Error ? unk : new Error(unk as string); 227 | this._log?.warn?.( 228 | `failed to decode ${chunk.length} byte chunk from tcp publisher ${this.toString()}: ${err}`, 229 | ); 230 | // Close the socket, the stream is now corrupt 231 | this._socket.close().catch((closeErr) => { 232 | this._log?.warn?.(`${this.toString()} close failed: ${closeErr}`); 233 | }); 234 | this.emit("error", err); 235 | } 236 | }; 237 | 238 | private _handleMessage = (msgData: Uint8Array): void => { 239 | if (this._shutdown) { 240 | this.close(); 241 | return; 242 | } 243 | 244 | this._stats.bytesReceived += msgData.byteLength; 245 | 246 | if (this._readingHeader) { 247 | this._readingHeader = false; 248 | 249 | this._header = TcpConnection.ParseHeader(msgData); 250 | this._msgDefinition = parseMessageDefinition(this._header.get("message_definition") ?? ""); 251 | this._msgReader = new MessageReader(this._msgDefinition); 252 | this.emit("header", this._header, this._msgDefinition, this._msgReader); 253 | } else { 254 | this._stats.messagesReceived++; 255 | 256 | if (this._msgReader != null) { 257 | try { 258 | const bytes = new Uint8Array(msgData.buffer, msgData.byteOffset, msgData.length); 259 | const msg = this._msgReader.readMessage(bytes); 260 | this.emit("message", msg, msgData); 261 | } catch (unk) { 262 | const err = unk instanceof Error ? unk : new Error(unk as string); 263 | this.emit("error", err); 264 | } 265 | } 266 | } 267 | }; 268 | 269 | static Uri(address: string, port: number): string { 270 | // RFC2732 requires IPv6 addresses that include ":" characters to be wrapped in "[]" brackets 271 | // when used in a URI 272 | const host = address.includes(":") ? `[${address}]` : address; 273 | return `tcpros://${host}:${port}`; 274 | } 275 | 276 | static SerializeHeader(header: Map): Uint8Array { 277 | const encoder = new TextEncoder(); 278 | const encoded = Array.from(header).map(([key, value]) => encoder.encode(`${key}=${value}`)); 279 | const payloadLen = encoded.reduce((sum, str) => sum + str.length + 4, 0); 280 | const buffer = new ArrayBuffer(payloadLen); 281 | const array = new Uint8Array(buffer); 282 | const view = new DataView(buffer); 283 | 284 | let idx = 0; 285 | encoded.forEach((strData) => { 286 | view.setUint32(idx, strData.length, true); 287 | idx += 4; 288 | array.set(strData, idx); 289 | idx += strData.length; 290 | }); 291 | 292 | return new Uint8Array(buffer); 293 | } 294 | 295 | static ParseHeader(data: Uint8Array): Map { 296 | const decoder = new TextDecoder(); 297 | const view = new DataView(data.buffer, data.byteOffset, data.byteLength); 298 | const result = new Map(); 299 | 300 | let idx = 0; 301 | while (idx + 4 < data.length) { 302 | const len = Math.min(view.getUint32(idx, true), data.length - idx - 4); 303 | idx += 4; 304 | const str = decoder.decode(new Uint8Array(data.buffer, data.byteOffset + idx, len)); 305 | let equalIdx = str.indexOf("="); 306 | if (equalIdx < 0) { 307 | equalIdx = str.length; 308 | } 309 | const key = str.substr(0, equalIdx); 310 | const value = str.substr(equalIdx + 1); 311 | result.set(key, value); 312 | idx += len; 313 | } 314 | 315 | return result; 316 | } 317 | } 318 | -------------------------------------------------------------------------------- /examples/ros1-chatter/yarn.lock: -------------------------------------------------------------------------------- 1 | # THIS IS AN AUTOGENERATED FILE. DO NOT EDIT THIS FILE DIRECTLY. 2 | # yarn lockfile v1 3 | 4 | 5 | "@cspotcode/source-map-consumer@0.8.0": 6 | version "0.8.0" 7 | resolved "https://registry.yarnpkg.com/@cspotcode/source-map-consumer/-/source-map-consumer-0.8.0.tgz#33bf4b7b39c178821606f669bbc447a6a629786b" 8 | integrity sha512-41qniHzTU8yAGbCp04ohlmSrZf8bkf/iJsl3V0dRGsQN/5GFfx+LbCSsCpp2gqrqjTVg/K6O8ycoV35JIwAzAg== 9 | 10 | "@cspotcode/source-map-support@0.7.0": 11 | version "0.7.0" 12 | resolved "https://registry.yarnpkg.com/@cspotcode/source-map-support/-/source-map-support-0.7.0.tgz#4789840aa859e46d2f3173727ab707c66bf344f5" 13 | integrity sha512-X4xqRHqN8ACt2aHVe51OxeA2HjbcL4MqFqXkrmQszJ1NOUuUu5u6Vqx/0lZSVNku7velL5FC/s5uEAj1lsBMhA== 14 | dependencies: 15 | "@cspotcode/source-map-consumer" "0.8.0" 16 | 17 | "@foxglove/just-fetch@^1.2.4": 18 | version "1.2.4" 19 | resolved "https://registry.yarnpkg.com/@foxglove/just-fetch/-/just-fetch-1.2.4.tgz#8d8bd2c6fee56a7e427f4879a832372d516afd7f" 20 | integrity sha512-2UnK19K/morE/zPF/oEkR+eGjQMulJ24Y0iXvhtHU4/fBT4vBJizqZ8vmdAJ4Tds6JrE0OtnRGGK+PF3+/2ssQ== 21 | dependencies: 22 | "@foxglove/node-fetch" "3.1.0" 23 | 24 | "@foxglove/node-fetch@3.1.0": 25 | version "3.1.0" 26 | resolved "https://registry.yarnpkg.com/@foxglove/node-fetch/-/node-fetch-3.1.0.tgz#4e721a5552626fdbec885fee23035e834926d916" 27 | integrity sha512-pfFDGz0lTI67MuX80LA0b6O/yv6if0rBYH5Bub/LCUAFvcvS7ubpluwsWCOhV0TyiC1wvbCX8/0j9BR1kBLiew== 28 | dependencies: 29 | data-uri-to-buffer "^3.0.1" 30 | fetch-blob "^2.1.1" 31 | 32 | "@foxglove/ros1@file:../..": 33 | version "1.4.2" 34 | dependencies: 35 | "@foxglove/rosmsg" "^2.0.0 || ^3.0.0" 36 | "@foxglove/rosmsg-serialization" "^1.2.3" 37 | "@foxglove/xmlrpc" "^1.2.1" 38 | eventemitter3 "^4.0.7" 39 | 40 | "@foxglove/rosmsg-serialization@^1.2.3": 41 | version "1.3.0" 42 | resolved "https://registry.yarnpkg.com/@foxglove/rosmsg-serialization/-/rosmsg-serialization-1.3.0.tgz#09df28ada98e117f71ed4f63e4ffee179d8a726e" 43 | integrity sha512-8at2IJOU9BrQ4PkDfbBXY5AU0SA9iXTQPfa6M0GEwDajjsl3J7SChJjoncDvNqW5UlcDIiqZg6r2EGs4imVIwQ== 44 | dependencies: 45 | "@foxglove/rosmsg" "^2.0.0 || ^3.0.0" 46 | 47 | "@foxglove/rosmsg@^2.0.0 || ^3.0.0": 48 | version "3.0.0" 49 | resolved "https://registry.yarnpkg.com/@foxglove/rosmsg/-/rosmsg-3.0.0.tgz#10ce39e42dab6804977cda297d0d317649184a16" 50 | integrity sha512-AAb3DMlLcuntUyEDBioDhbjdbKivC1hj7Gnu7QXX8ce+R50V8xs5sfxccsjE6N0Qs+eQxuzLhT2kW3mNXT/gbg== 51 | dependencies: 52 | md5-typescript "^1.0.5" 53 | 54 | "@foxglove/xmlrpc@^1.2.1": 55 | version "1.2.1" 56 | resolved "https://registry.yarnpkg.com/@foxglove/xmlrpc/-/xmlrpc-1.2.1.tgz#368ece22e71073755735ef81771efbbc1bb6e614" 57 | integrity sha512-bZrMh/Hp3QzOhM0oUC5Hn+9VB70cXK0eWJtud647+c1X6q2T89ZlOz4YPSeiIZE2QRMwOhwokJz/T37vfN4LOw== 58 | dependencies: 59 | "@foxglove/just-fetch" "^1.2.4" 60 | byte-base64 "^1.1.0" 61 | sax "^1.2.4" 62 | xmlbuilder2 "^3.0.2" 63 | 64 | "@oozcitak/dom@1.15.10": 65 | version "1.15.10" 66 | resolved "https://registry.yarnpkg.com/@oozcitak/dom/-/dom-1.15.10.tgz#dca7289f2b292cff2a901ea4fbbcc0a1ab0b05c2" 67 | integrity sha512-0JT29/LaxVgRcGKvHmSrUTEvZ8BXvZhGl2LASRUgHqDTC1M5g1pLmVv56IYNyt3bG2CUjDkc67wnyZC14pbQrQ== 68 | dependencies: 69 | "@oozcitak/infra" "1.0.8" 70 | "@oozcitak/url" "1.0.4" 71 | "@oozcitak/util" "8.3.8" 72 | 73 | "@oozcitak/infra@1.0.8": 74 | version "1.0.8" 75 | resolved "https://registry.yarnpkg.com/@oozcitak/infra/-/infra-1.0.8.tgz#b0b089421f7d0f6878687608301fbaba837a7d17" 76 | integrity sha512-JRAUc9VR6IGHOL7OGF+yrvs0LO8SlqGnPAMqyzOuFZPSZSXI7Xf2O9+awQPSMXgIWGtgUf/dA6Hs6X6ySEaWTg== 77 | dependencies: 78 | "@oozcitak/util" "8.3.8" 79 | 80 | "@oozcitak/url@1.0.4": 81 | version "1.0.4" 82 | resolved "https://registry.yarnpkg.com/@oozcitak/url/-/url-1.0.4.tgz#ca8b1c876319cf5a648dfa1123600a6aa5cda6ba" 83 | integrity sha512-kDcD8y+y3FCSOvnBI6HJgl00viO/nGbQoCINmQ0h98OhnGITrWR3bOGfwYCthgcrV8AnTJz8MzslTQbC3SOAmw== 84 | dependencies: 85 | "@oozcitak/infra" "1.0.8" 86 | "@oozcitak/util" "8.3.8" 87 | 88 | "@oozcitak/util@8.3.8": 89 | version "8.3.8" 90 | resolved "https://registry.yarnpkg.com/@oozcitak/util/-/util-8.3.8.tgz#10f65fe1891fd8cde4957360835e78fd1936bfdd" 91 | integrity sha512-T8TbSnGsxo6TDBJx/Sgv/BlVJL3tshxZP7Aq5R1mSnM5OcHY2dQaxLMu2+E8u3gN0MLOzdjurqN4ZRVuzQycOQ== 92 | 93 | "@tsconfig/node10@^1.0.7": 94 | version "1.0.8" 95 | resolved "https://registry.yarnpkg.com/@tsconfig/node10/-/node10-1.0.8.tgz#c1e4e80d6f964fbecb3359c43bd48b40f7cadad9" 96 | integrity sha512-6XFfSQmMgq0CFLY1MslA/CPUfhIL919M1rMsa5lP2P097N2Wd1sSX0tx1u4olM16fLNhtHZpRhedZJphNJqmZg== 97 | 98 | "@tsconfig/node12@^1.0.7": 99 | version "1.0.9" 100 | resolved "https://registry.yarnpkg.com/@tsconfig/node12/-/node12-1.0.9.tgz#62c1f6dee2ebd9aead80dc3afa56810e58e1a04c" 101 | integrity sha512-/yBMcem+fbvhSREH+s14YJi18sp7J9jpuhYByADT2rypfajMZZN4WQ6zBGgBKp53NKmqI36wFYDb3yaMPurITw== 102 | 103 | "@tsconfig/node14@^1.0.0": 104 | version "1.0.1" 105 | resolved "https://registry.yarnpkg.com/@tsconfig/node14/-/node14-1.0.1.tgz#95f2d167ffb9b8d2068b0b235302fafd4df711f2" 106 | integrity sha512-509r2+yARFfHHE7T6Puu2jjkoycftovhXRqW328PDXTVGKihlb1P8Z9mMZH04ebyajfRY7dedfGynlrFHJUQCg== 107 | 108 | "@tsconfig/node16@^1.0.2": 109 | version "1.0.2" 110 | resolved "https://registry.yarnpkg.com/@tsconfig/node16/-/node16-1.0.2.tgz#423c77877d0569db20e1fc80885ac4118314010e" 111 | integrity sha512-eZxlbI8GZscaGS7kkc/trHTT5xgrjH3/1n2JDwusC9iahPKWMRvRjJSAN5mCXviuTGQ/lHnhvv8Q1YTpnfz9gA== 112 | 113 | "@types/node@*": 114 | version "17.0.27" 115 | resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.27.tgz#f4df3981ae8268c066e8f49995639f855469081e" 116 | integrity sha512-4/Ke7bbWOasuT3kceBZFGakP1dYN2XFd8v2l9bqF2LNWrmeU07JLpp56aEeG6+Q3olqO5TvXpW0yaiYnZJ5CXg== 117 | 118 | acorn-walk@^8.1.1: 119 | version "8.2.0" 120 | resolved "https://registry.yarnpkg.com/acorn-walk/-/acorn-walk-8.2.0.tgz#741210f2e2426454508853a2f44d0ab83b7f69c1" 121 | integrity sha512-k+iyHEuPgSw6SbuDpGQM+06HQUa04DZ3o+F6CSzXMvvI5KMvnaEqXe+YVe555R9nn6GPt404fos4wcgpw12SDA== 122 | 123 | acorn@^8.4.1: 124 | version "8.7.0" 125 | resolved "https://registry.yarnpkg.com/acorn/-/acorn-8.7.0.tgz#90951fde0f8f09df93549481e5fc141445b791cf" 126 | integrity sha512-V/LGr1APy+PXIwKebEWrkZPwoeoF+w1jiOBUmuxuiUIaOHtob8Qc9BTrYo7VuI5fR8tqsy+buA2WFooR5olqvQ== 127 | 128 | arg@^4.1.0: 129 | version "4.1.3" 130 | resolved "https://registry.yarnpkg.com/arg/-/arg-4.1.3.tgz#269fc7ad5b8e42cb63c896d5666017261c144089" 131 | integrity sha512-58S9QDqG0Xx27YwPSt9fJxivjYl432YCwfDMfZ+71RAqUrZef7LrKQZ3LHLOwCS4FLNBplP533Zx895SeOCHvA== 132 | 133 | argparse@^1.0.7: 134 | version "1.0.10" 135 | resolved "https://registry.yarnpkg.com/argparse/-/argparse-1.0.10.tgz#bcd6791ea5ae09725e17e5ad988134cd40b3d911" 136 | integrity sha512-o5Roy6tNG4SL/FOkCAN6RzjiakZS25RLYFrcMttJqbdd8BWrnA+fGz57iN5Pb06pvBGvl5gQ0B48dJlslXvoTg== 137 | dependencies: 138 | sprintf-js "~1.0.2" 139 | 140 | byte-base64@^1.1.0: 141 | version "1.1.0" 142 | resolved "https://registry.yarnpkg.com/byte-base64/-/byte-base64-1.1.0.tgz#e28afbdc9d122c9d3ca716b8b5cc696dbedf8d08" 143 | integrity sha512-56cXelkJrVMdCY9V/3RfDxTh4VfMFCQ5km7B7GkIGfo4bcPL9aACyJLB0Ms3Ezu5rsHmLB2suis96z4fLM03DA== 144 | 145 | create-require@^1.1.0: 146 | version "1.1.1" 147 | resolved "https://registry.yarnpkg.com/create-require/-/create-require-1.1.1.tgz#c1d7e8f1e5f6cfc9ff65f9cd352d37348756c333" 148 | integrity sha512-dcKFX3jn0MpIaXjisoRvexIJVEKzaq7z2rZKxf+MSr9TkdmHmsU4m2lcLojrj/FHl8mk5VxMmYA+ftRkP/3oKQ== 149 | 150 | data-uri-to-buffer@^3.0.1: 151 | version "3.0.1" 152 | resolved "https://registry.yarnpkg.com/data-uri-to-buffer/-/data-uri-to-buffer-3.0.1.tgz#594b8973938c5bc2c33046535785341abc4f3636" 153 | integrity sha512-WboRycPNsVw3B3TL559F7kuBUM4d8CgMEvk6xEJlOp7OBPjt6G7z8WMWlD2rOFZLk6OYfFIUGsCOWzcQH9K2og== 154 | 155 | diff@^4.0.1: 156 | version "4.0.2" 157 | resolved "https://registry.yarnpkg.com/diff/-/diff-4.0.2.tgz#60f3aecb89d5fae520c11aa19efc2bb982aade7d" 158 | integrity sha512-58lmxKSA4BNyLz+HHMUzlOEpg09FV+ev6ZMe3vJihgdxzgcwZ8VoEEPmALCZG9LmqfVoNMMKpttIYTVG6uDY7A== 159 | 160 | esprima@^4.0.0: 161 | version "4.0.1" 162 | resolved "https://registry.yarnpkg.com/esprima/-/esprima-4.0.1.tgz#13b04cdb3e6c5d19df91ab6987a8695619b0aa71" 163 | integrity sha512-eGuFFw7Upda+g4p+QHvnW0RyTX/SVeJBDM/gCtMARO0cLuT2HcEKnTPvhjV6aGeqrCB/sbNop0Kszm0jsaWU4A== 164 | 165 | eventemitter3@^4.0.7: 166 | version "4.0.7" 167 | resolved "https://registry.yarnpkg.com/eventemitter3/-/eventemitter3-4.0.7.tgz#2de9b68f6528d5644ef5c59526a1b4a07306169f" 168 | integrity sha512-8guHBZCwKnFhYdHr2ysuRWErTwhoN2X8XELRlrRwpmfeY2jjuUN4taQMsULKUVo1K4DvZl+0pgfyoysHxvmvEw== 169 | 170 | fetch-blob@^2.1.1: 171 | version "2.1.2" 172 | resolved "https://registry.yarnpkg.com/fetch-blob/-/fetch-blob-2.1.2.tgz#a7805db1361bd44c1ef62bb57fb5fe8ea173ef3c" 173 | integrity sha512-YKqtUDwqLyfyMnmbw8XD6Q8j9i/HggKtPEI+pZ1+8bvheBu78biSmNaXWusx1TauGqtUUGx/cBb1mKdq2rLYow== 174 | 175 | js-yaml@3.14.0: 176 | version "3.14.0" 177 | resolved "https://registry.yarnpkg.com/js-yaml/-/js-yaml-3.14.0.tgz#a7a34170f26a21bb162424d8adacb4113a69e482" 178 | integrity sha512-/4IbIeHcD9VMHFqDR/gQ7EdZdLimOvW2DdcxFjdyyZ9NsbS+ccrXqVWDtab/lRl5AlUqmpBx8EhPaWR+OtY17A== 179 | dependencies: 180 | argparse "^1.0.7" 181 | esprima "^4.0.0" 182 | 183 | make-error@^1.1.1: 184 | version "1.3.6" 185 | resolved "https://registry.yarnpkg.com/make-error/-/make-error-1.3.6.tgz#2eb2e37ea9b67c4891f684a1394799af484cf7a2" 186 | integrity sha512-s8UhlNe7vPKomQhC1qFelMokr/Sc3AgNbso3n74mVPA5LTZwkB9NlXf4XPamLxJE8h0gh73rM94xvwRT2CVInw== 187 | 188 | md5-typescript@^1.0.5: 189 | version "1.0.5" 190 | resolved "https://registry.yarnpkg.com/md5-typescript/-/md5-typescript-1.0.5.tgz#68c0b24dff8e5d3162e498fa9893b63be72e038f" 191 | integrity sha1-aMCyTf+OXTFi5Jj6mJO2O+cuA48= 192 | 193 | sax@^1.2.4: 194 | version "1.2.4" 195 | resolved "https://registry.yarnpkg.com/sax/-/sax-1.2.4.tgz#2816234e2378bddc4e5354fab5caa895df7100d9" 196 | integrity sha512-NqVDv9TpANUjFm0N8uM5GxL36UgKi9/atZw+x7YFnQ8ckwFGKrl4xX4yWtrey3UJm5nP1kUbnYgLopqWNSRhWw== 197 | 198 | sprintf-js@~1.0.2: 199 | version "1.0.3" 200 | resolved "https://registry.yarnpkg.com/sprintf-js/-/sprintf-js-1.0.3.tgz#04e6926f662895354f3dd015203633b857297e2c" 201 | integrity sha1-BOaSb2YolTVPPdAVIDYzuFcpfiw= 202 | 203 | ts-node@10.7.0: 204 | version "10.7.0" 205 | resolved "https://registry.yarnpkg.com/ts-node/-/ts-node-10.7.0.tgz#35d503d0fab3e2baa672a0e94f4b40653c2463f5" 206 | integrity sha512-TbIGS4xgJoX2i3do417KSaep1uRAW/Lu+WAL2doDHC0D6ummjirVOXU5/7aiZotbQ5p1Zp9tP7U6cYhA0O7M8A== 207 | dependencies: 208 | "@cspotcode/source-map-support" "0.7.0" 209 | "@tsconfig/node10" "^1.0.7" 210 | "@tsconfig/node12" "^1.0.7" 211 | "@tsconfig/node14" "^1.0.0" 212 | "@tsconfig/node16" "^1.0.2" 213 | acorn "^8.4.1" 214 | acorn-walk "^8.1.1" 215 | arg "^4.1.0" 216 | create-require "^1.1.0" 217 | diff "^4.0.1" 218 | make-error "^1.1.1" 219 | v8-compile-cache-lib "^3.0.0" 220 | yn "3.1.1" 221 | 222 | tslib@2.1.0: 223 | version "2.1.0" 224 | resolved "https://registry.yarnpkg.com/tslib/-/tslib-2.1.0.tgz#da60860f1c2ecaa5703ab7d39bc05b6bf988b97a" 225 | integrity sha512-hcVC3wYEziELGGmEEXue7D75zbwIIVUMWAVbHItGPx0ziyXxrOMQx4rQEVEV45Ut/1IotuEvwqPopzIOkDMf0A== 226 | 227 | typescript@4.5.2: 228 | version "4.5.2" 229 | resolved "https://registry.yarnpkg.com/typescript/-/typescript-4.5.2.tgz#8ac1fba9f52256fdb06fb89e4122fa6a346c2998" 230 | integrity sha512-5BlMof9H1yGt0P8/WF+wPNw6GfctgGjXp5hkblpyT+8rkASSmkUKMXrxR0Xg8ThVCi/JnHQiKXeBaEwCeQwMFw== 231 | 232 | v8-compile-cache-lib@^3.0.0: 233 | version "3.0.1" 234 | resolved "https://registry.yarnpkg.com/v8-compile-cache-lib/-/v8-compile-cache-lib-3.0.1.tgz#6336e8d71965cb3d35a1bbb7868445a7c05264bf" 235 | integrity sha512-wa7YjyUGfNZngI/vtK0UHAN+lgDCxBPCylVXGp0zu59Fz5aiGtNXaq3DhIov063MorB+VfufLh3JlF2KdTK3xg== 236 | 237 | xmlbuilder2@^3.0.2: 238 | version "3.0.2" 239 | resolved "https://registry.yarnpkg.com/xmlbuilder2/-/xmlbuilder2-3.0.2.tgz#fc499688b35a916f269e7b459c2fa02bb5c0822a" 240 | integrity sha512-h4MUawGY21CTdhV4xm3DG9dgsqyhDkZvVJBx88beqX8wJs3VgyGQgAn5VreHuae6unTQxh115aMK5InCVmOIKw== 241 | dependencies: 242 | "@oozcitak/dom" "1.15.10" 243 | "@oozcitak/infra" "1.0.8" 244 | "@oozcitak/util" "8.3.8" 245 | "@types/node" "*" 246 | js-yaml "3.14.0" 247 | 248 | yn@3.1.1: 249 | version "3.1.1" 250 | resolved "https://registry.yarnpkg.com/yn/-/yn-3.1.1.tgz#1e87401a09d767c1d5eab26a6e4c185182d2eb50" 251 | integrity sha512-Ux4ygGWsu2c7isFWe8Yu1YluJmqVhxqK2cLXNQA5AcC3QfbGNpM7fu0Y8b/z16pXLnFxZYvWhd3fhBY9DLmC6Q== 252 | -------------------------------------------------------------------------------- /examples/ros1-turtlesim-test/yarn.lock: -------------------------------------------------------------------------------- 1 | # THIS IS AN AUTOGENERATED FILE. DO NOT EDIT THIS FILE DIRECTLY. 2 | # yarn lockfile v1 3 | 4 | 5 | "@cspotcode/source-map-consumer@0.8.0": 6 | version "0.8.0" 7 | resolved "https://registry.yarnpkg.com/@cspotcode/source-map-consumer/-/source-map-consumer-0.8.0.tgz#33bf4b7b39c178821606f669bbc447a6a629786b" 8 | integrity sha512-41qniHzTU8yAGbCp04ohlmSrZf8bkf/iJsl3V0dRGsQN/5GFfx+LbCSsCpp2gqrqjTVg/K6O8ycoV35JIwAzAg== 9 | 10 | "@cspotcode/source-map-support@0.7.0": 11 | version "0.7.0" 12 | resolved "https://registry.yarnpkg.com/@cspotcode/source-map-support/-/source-map-support-0.7.0.tgz#4789840aa859e46d2f3173727ab707c66bf344f5" 13 | integrity sha512-X4xqRHqN8ACt2aHVe51OxeA2HjbcL4MqFqXkrmQszJ1NOUuUu5u6Vqx/0lZSVNku7velL5FC/s5uEAj1lsBMhA== 14 | dependencies: 15 | "@cspotcode/source-map-consumer" "0.8.0" 16 | 17 | "@foxglove/just-fetch@^1.2.4": 18 | version "1.2.4" 19 | resolved "https://registry.yarnpkg.com/@foxglove/just-fetch/-/just-fetch-1.2.4.tgz#8d8bd2c6fee56a7e427f4879a832372d516afd7f" 20 | integrity sha512-2UnK19K/morE/zPF/oEkR+eGjQMulJ24Y0iXvhtHU4/fBT4vBJizqZ8vmdAJ4Tds6JrE0OtnRGGK+PF3+/2ssQ== 21 | dependencies: 22 | "@foxglove/node-fetch" "3.1.0" 23 | 24 | "@foxglove/node-fetch@3.1.0": 25 | version "3.1.0" 26 | resolved "https://registry.yarnpkg.com/@foxglove/node-fetch/-/node-fetch-3.1.0.tgz#4e721a5552626fdbec885fee23035e834926d916" 27 | integrity sha512-pfFDGz0lTI67MuX80LA0b6O/yv6if0rBYH5Bub/LCUAFvcvS7ubpluwsWCOhV0TyiC1wvbCX8/0j9BR1kBLiew== 28 | dependencies: 29 | data-uri-to-buffer "^3.0.1" 30 | fetch-blob "^2.1.1" 31 | 32 | "@foxglove/ros1@file:../..": 33 | version "1.4.2" 34 | dependencies: 35 | "@foxglove/rosmsg" "^2.0.0 || ^3.0.0" 36 | "@foxglove/rosmsg-serialization" "^1.2.3" 37 | "@foxglove/xmlrpc" "^1.2.1" 38 | eventemitter3 "^4.0.7" 39 | 40 | "@foxglove/rosmsg-serialization@^1.2.3": 41 | version "1.3.0" 42 | resolved "https://registry.yarnpkg.com/@foxglove/rosmsg-serialization/-/rosmsg-serialization-1.3.0.tgz#09df28ada98e117f71ed4f63e4ffee179d8a726e" 43 | integrity sha512-8at2IJOU9BrQ4PkDfbBXY5AU0SA9iXTQPfa6M0GEwDajjsl3J7SChJjoncDvNqW5UlcDIiqZg6r2EGs4imVIwQ== 44 | dependencies: 45 | "@foxglove/rosmsg" "^2.0.0 || ^3.0.0" 46 | 47 | "@foxglove/rosmsg@^2.0.0 || ^3.0.0": 48 | version "3.0.0" 49 | resolved "https://registry.yarnpkg.com/@foxglove/rosmsg/-/rosmsg-3.0.0.tgz#10ce39e42dab6804977cda297d0d317649184a16" 50 | integrity sha512-AAb3DMlLcuntUyEDBioDhbjdbKivC1hj7Gnu7QXX8ce+R50V8xs5sfxccsjE6N0Qs+eQxuzLhT2kW3mNXT/gbg== 51 | dependencies: 52 | md5-typescript "^1.0.5" 53 | 54 | "@foxglove/xmlrpc@^1.2.1": 55 | version "1.2.1" 56 | resolved "https://registry.yarnpkg.com/@foxglove/xmlrpc/-/xmlrpc-1.2.1.tgz#368ece22e71073755735ef81771efbbc1bb6e614" 57 | integrity sha512-bZrMh/Hp3QzOhM0oUC5Hn+9VB70cXK0eWJtud647+c1X6q2T89ZlOz4YPSeiIZE2QRMwOhwokJz/T37vfN4LOw== 58 | dependencies: 59 | "@foxglove/just-fetch" "^1.2.4" 60 | byte-base64 "^1.1.0" 61 | sax "^1.2.4" 62 | xmlbuilder2 "^3.0.2" 63 | 64 | "@oozcitak/dom@1.15.10": 65 | version "1.15.10" 66 | resolved "https://registry.yarnpkg.com/@oozcitak/dom/-/dom-1.15.10.tgz#dca7289f2b292cff2a901ea4fbbcc0a1ab0b05c2" 67 | integrity sha512-0JT29/LaxVgRcGKvHmSrUTEvZ8BXvZhGl2LASRUgHqDTC1M5g1pLmVv56IYNyt3bG2CUjDkc67wnyZC14pbQrQ== 68 | dependencies: 69 | "@oozcitak/infra" "1.0.8" 70 | "@oozcitak/url" "1.0.4" 71 | "@oozcitak/util" "8.3.8" 72 | 73 | "@oozcitak/infra@1.0.8": 74 | version "1.0.8" 75 | resolved "https://registry.yarnpkg.com/@oozcitak/infra/-/infra-1.0.8.tgz#b0b089421f7d0f6878687608301fbaba837a7d17" 76 | integrity sha512-JRAUc9VR6IGHOL7OGF+yrvs0LO8SlqGnPAMqyzOuFZPSZSXI7Xf2O9+awQPSMXgIWGtgUf/dA6Hs6X6ySEaWTg== 77 | dependencies: 78 | "@oozcitak/util" "8.3.8" 79 | 80 | "@oozcitak/url@1.0.4": 81 | version "1.0.4" 82 | resolved "https://registry.yarnpkg.com/@oozcitak/url/-/url-1.0.4.tgz#ca8b1c876319cf5a648dfa1123600a6aa5cda6ba" 83 | integrity sha512-kDcD8y+y3FCSOvnBI6HJgl00viO/nGbQoCINmQ0h98OhnGITrWR3bOGfwYCthgcrV8AnTJz8MzslTQbC3SOAmw== 84 | dependencies: 85 | "@oozcitak/infra" "1.0.8" 86 | "@oozcitak/util" "8.3.8" 87 | 88 | "@oozcitak/util@8.3.8": 89 | version "8.3.8" 90 | resolved "https://registry.yarnpkg.com/@oozcitak/util/-/util-8.3.8.tgz#10f65fe1891fd8cde4957360835e78fd1936bfdd" 91 | integrity sha512-T8TbSnGsxo6TDBJx/Sgv/BlVJL3tshxZP7Aq5R1mSnM5OcHY2dQaxLMu2+E8u3gN0MLOzdjurqN4ZRVuzQycOQ== 92 | 93 | "@tsconfig/node10@^1.0.7": 94 | version "1.0.8" 95 | resolved "https://registry.yarnpkg.com/@tsconfig/node10/-/node10-1.0.8.tgz#c1e4e80d6f964fbecb3359c43bd48b40f7cadad9" 96 | integrity sha512-6XFfSQmMgq0CFLY1MslA/CPUfhIL919M1rMsa5lP2P097N2Wd1sSX0tx1u4olM16fLNhtHZpRhedZJphNJqmZg== 97 | 98 | "@tsconfig/node12@^1.0.7": 99 | version "1.0.9" 100 | resolved "https://registry.yarnpkg.com/@tsconfig/node12/-/node12-1.0.9.tgz#62c1f6dee2ebd9aead80dc3afa56810e58e1a04c" 101 | integrity sha512-/yBMcem+fbvhSREH+s14YJi18sp7J9jpuhYByADT2rypfajMZZN4WQ6zBGgBKp53NKmqI36wFYDb3yaMPurITw== 102 | 103 | "@tsconfig/node14@^1.0.0": 104 | version "1.0.1" 105 | resolved "https://registry.yarnpkg.com/@tsconfig/node14/-/node14-1.0.1.tgz#95f2d167ffb9b8d2068b0b235302fafd4df711f2" 106 | integrity sha512-509r2+yARFfHHE7T6Puu2jjkoycftovhXRqW328PDXTVGKihlb1P8Z9mMZH04ebyajfRY7dedfGynlrFHJUQCg== 107 | 108 | "@tsconfig/node16@^1.0.2": 109 | version "1.0.2" 110 | resolved "https://registry.yarnpkg.com/@tsconfig/node16/-/node16-1.0.2.tgz#423c77877d0569db20e1fc80885ac4118314010e" 111 | integrity sha512-eZxlbI8GZscaGS7kkc/trHTT5xgrjH3/1n2JDwusC9iahPKWMRvRjJSAN5mCXviuTGQ/lHnhvv8Q1YTpnfz9gA== 112 | 113 | "@types/node@*": 114 | version "17.0.27" 115 | resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.27.tgz#f4df3981ae8268c066e8f49995639f855469081e" 116 | integrity sha512-4/Ke7bbWOasuT3kceBZFGakP1dYN2XFd8v2l9bqF2LNWrmeU07JLpp56aEeG6+Q3olqO5TvXpW0yaiYnZJ5CXg== 117 | 118 | acorn-walk@^8.1.1: 119 | version "8.2.0" 120 | resolved "https://registry.yarnpkg.com/acorn-walk/-/acorn-walk-8.2.0.tgz#741210f2e2426454508853a2f44d0ab83b7f69c1" 121 | integrity sha512-k+iyHEuPgSw6SbuDpGQM+06HQUa04DZ3o+F6CSzXMvvI5KMvnaEqXe+YVe555R9nn6GPt404fos4wcgpw12SDA== 122 | 123 | acorn@^8.4.1: 124 | version "8.7.0" 125 | resolved "https://registry.yarnpkg.com/acorn/-/acorn-8.7.0.tgz#90951fde0f8f09df93549481e5fc141445b791cf" 126 | integrity sha512-V/LGr1APy+PXIwKebEWrkZPwoeoF+w1jiOBUmuxuiUIaOHtob8Qc9BTrYo7VuI5fR8tqsy+buA2WFooR5olqvQ== 127 | 128 | arg@^4.1.0: 129 | version "4.1.3" 130 | resolved "https://registry.yarnpkg.com/arg/-/arg-4.1.3.tgz#269fc7ad5b8e42cb63c896d5666017261c144089" 131 | integrity sha512-58S9QDqG0Xx27YwPSt9fJxivjYl432YCwfDMfZ+71RAqUrZef7LrKQZ3LHLOwCS4FLNBplP533Zx895SeOCHvA== 132 | 133 | argparse@^1.0.7: 134 | version "1.0.10" 135 | resolved "https://registry.yarnpkg.com/argparse/-/argparse-1.0.10.tgz#bcd6791ea5ae09725e17e5ad988134cd40b3d911" 136 | integrity sha512-o5Roy6tNG4SL/FOkCAN6RzjiakZS25RLYFrcMttJqbdd8BWrnA+fGz57iN5Pb06pvBGvl5gQ0B48dJlslXvoTg== 137 | dependencies: 138 | sprintf-js "~1.0.2" 139 | 140 | byte-base64@^1.1.0: 141 | version "1.1.0" 142 | resolved "https://registry.yarnpkg.com/byte-base64/-/byte-base64-1.1.0.tgz#e28afbdc9d122c9d3ca716b8b5cc696dbedf8d08" 143 | integrity sha512-56cXelkJrVMdCY9V/3RfDxTh4VfMFCQ5km7B7GkIGfo4bcPL9aACyJLB0Ms3Ezu5rsHmLB2suis96z4fLM03DA== 144 | 145 | create-require@^1.1.0: 146 | version "1.1.1" 147 | resolved "https://registry.yarnpkg.com/create-require/-/create-require-1.1.1.tgz#c1d7e8f1e5f6cfc9ff65f9cd352d37348756c333" 148 | integrity sha512-dcKFX3jn0MpIaXjisoRvexIJVEKzaq7z2rZKxf+MSr9TkdmHmsU4m2lcLojrj/FHl8mk5VxMmYA+ftRkP/3oKQ== 149 | 150 | data-uri-to-buffer@^3.0.1: 151 | version "3.0.1" 152 | resolved "https://registry.yarnpkg.com/data-uri-to-buffer/-/data-uri-to-buffer-3.0.1.tgz#594b8973938c5bc2c33046535785341abc4f3636" 153 | integrity sha512-WboRycPNsVw3B3TL559F7kuBUM4d8CgMEvk6xEJlOp7OBPjt6G7z8WMWlD2rOFZLk6OYfFIUGsCOWzcQH9K2og== 154 | 155 | diff@^4.0.1: 156 | version "4.0.2" 157 | resolved "https://registry.yarnpkg.com/diff/-/diff-4.0.2.tgz#60f3aecb89d5fae520c11aa19efc2bb982aade7d" 158 | integrity sha512-58lmxKSA4BNyLz+HHMUzlOEpg09FV+ev6ZMe3vJihgdxzgcwZ8VoEEPmALCZG9LmqfVoNMMKpttIYTVG6uDY7A== 159 | 160 | esprima@^4.0.0: 161 | version "4.0.1" 162 | resolved "https://registry.yarnpkg.com/esprima/-/esprima-4.0.1.tgz#13b04cdb3e6c5d19df91ab6987a8695619b0aa71" 163 | integrity sha512-eGuFFw7Upda+g4p+QHvnW0RyTX/SVeJBDM/gCtMARO0cLuT2HcEKnTPvhjV6aGeqrCB/sbNop0Kszm0jsaWU4A== 164 | 165 | eventemitter3@^4.0.7: 166 | version "4.0.7" 167 | resolved "https://registry.yarnpkg.com/eventemitter3/-/eventemitter3-4.0.7.tgz#2de9b68f6528d5644ef5c59526a1b4a07306169f" 168 | integrity sha512-8guHBZCwKnFhYdHr2ysuRWErTwhoN2X8XELRlrRwpmfeY2jjuUN4taQMsULKUVo1K4DvZl+0pgfyoysHxvmvEw== 169 | 170 | fetch-blob@^2.1.1: 171 | version "2.1.2" 172 | resolved "https://registry.yarnpkg.com/fetch-blob/-/fetch-blob-2.1.2.tgz#a7805db1361bd44c1ef62bb57fb5fe8ea173ef3c" 173 | integrity sha512-YKqtUDwqLyfyMnmbw8XD6Q8j9i/HggKtPEI+pZ1+8bvheBu78biSmNaXWusx1TauGqtUUGx/cBb1mKdq2rLYow== 174 | 175 | js-yaml@3.14.0: 176 | version "3.14.0" 177 | resolved "https://registry.yarnpkg.com/js-yaml/-/js-yaml-3.14.0.tgz#a7a34170f26a21bb162424d8adacb4113a69e482" 178 | integrity sha512-/4IbIeHcD9VMHFqDR/gQ7EdZdLimOvW2DdcxFjdyyZ9NsbS+ccrXqVWDtab/lRl5AlUqmpBx8EhPaWR+OtY17A== 179 | dependencies: 180 | argparse "^1.0.7" 181 | esprima "^4.0.0" 182 | 183 | make-error@^1.1.1: 184 | version "1.3.6" 185 | resolved "https://registry.yarnpkg.com/make-error/-/make-error-1.3.6.tgz#2eb2e37ea9b67c4891f684a1394799af484cf7a2" 186 | integrity sha512-s8UhlNe7vPKomQhC1qFelMokr/Sc3AgNbso3n74mVPA5LTZwkB9NlXf4XPamLxJE8h0gh73rM94xvwRT2CVInw== 187 | 188 | md5-typescript@^1.0.5: 189 | version "1.0.5" 190 | resolved "https://registry.yarnpkg.com/md5-typescript/-/md5-typescript-1.0.5.tgz#68c0b24dff8e5d3162e498fa9893b63be72e038f" 191 | integrity sha1-aMCyTf+OXTFi5Jj6mJO2O+cuA48= 192 | 193 | sax@^1.2.4: 194 | version "1.2.4" 195 | resolved "https://registry.yarnpkg.com/sax/-/sax-1.2.4.tgz#2816234e2378bddc4e5354fab5caa895df7100d9" 196 | integrity sha512-NqVDv9TpANUjFm0N8uM5GxL36UgKi9/atZw+x7YFnQ8ckwFGKrl4xX4yWtrey3UJm5nP1kUbnYgLopqWNSRhWw== 197 | 198 | sprintf-js@~1.0.2: 199 | version "1.0.3" 200 | resolved "https://registry.yarnpkg.com/sprintf-js/-/sprintf-js-1.0.3.tgz#04e6926f662895354f3dd015203633b857297e2c" 201 | integrity sha1-BOaSb2YolTVPPdAVIDYzuFcpfiw= 202 | 203 | ts-node@10.7.0: 204 | version "10.7.0" 205 | resolved "https://registry.yarnpkg.com/ts-node/-/ts-node-10.7.0.tgz#35d503d0fab3e2baa672a0e94f4b40653c2463f5" 206 | integrity sha512-TbIGS4xgJoX2i3do417KSaep1uRAW/Lu+WAL2doDHC0D6ummjirVOXU5/7aiZotbQ5p1Zp9tP7U6cYhA0O7M8A== 207 | dependencies: 208 | "@cspotcode/source-map-support" "0.7.0" 209 | "@tsconfig/node10" "^1.0.7" 210 | "@tsconfig/node12" "^1.0.7" 211 | "@tsconfig/node14" "^1.0.0" 212 | "@tsconfig/node16" "^1.0.2" 213 | acorn "^8.4.1" 214 | acorn-walk "^8.1.1" 215 | arg "^4.1.0" 216 | create-require "^1.1.0" 217 | diff "^4.0.1" 218 | make-error "^1.1.1" 219 | v8-compile-cache-lib "^3.0.0" 220 | yn "3.1.1" 221 | 222 | tslib@2.1.0: 223 | version "2.1.0" 224 | resolved "https://registry.yarnpkg.com/tslib/-/tslib-2.1.0.tgz#da60860f1c2ecaa5703ab7d39bc05b6bf988b97a" 225 | integrity sha512-hcVC3wYEziELGGmEEXue7D75zbwIIVUMWAVbHItGPx0ziyXxrOMQx4rQEVEV45Ut/1IotuEvwqPopzIOkDMf0A== 226 | 227 | typescript@4.5.2: 228 | version "4.5.2" 229 | resolved "https://registry.yarnpkg.com/typescript/-/typescript-4.5.2.tgz#8ac1fba9f52256fdb06fb89e4122fa6a346c2998" 230 | integrity sha512-5BlMof9H1yGt0P8/WF+wPNw6GfctgGjXp5hkblpyT+8rkASSmkUKMXrxR0Xg8ThVCi/JnHQiKXeBaEwCeQwMFw== 231 | 232 | v8-compile-cache-lib@^3.0.0: 233 | version "3.0.1" 234 | resolved "https://registry.yarnpkg.com/v8-compile-cache-lib/-/v8-compile-cache-lib-3.0.1.tgz#6336e8d71965cb3d35a1bbb7868445a7c05264bf" 235 | integrity sha512-wa7YjyUGfNZngI/vtK0UHAN+lgDCxBPCylVXGp0zu59Fz5aiGtNXaq3DhIov063MorB+VfufLh3JlF2KdTK3xg== 236 | 237 | xmlbuilder2@^3.0.2: 238 | version "3.0.2" 239 | resolved "https://registry.yarnpkg.com/xmlbuilder2/-/xmlbuilder2-3.0.2.tgz#fc499688b35a916f269e7b459c2fa02bb5c0822a" 240 | integrity sha512-h4MUawGY21CTdhV4xm3DG9dgsqyhDkZvVJBx88beqX8wJs3VgyGQgAn5VreHuae6unTQxh115aMK5InCVmOIKw== 241 | dependencies: 242 | "@oozcitak/dom" "1.15.10" 243 | "@oozcitak/infra" "1.0.8" 244 | "@oozcitak/util" "8.3.8" 245 | "@types/node" "*" 246 | js-yaml "3.14.0" 247 | 248 | yn@3.1.1: 249 | version "3.1.1" 250 | resolved "https://registry.yarnpkg.com/yn/-/yn-3.1.1.tgz#1e87401a09d767c1d5eab26a6e4c185182d2eb50" 251 | integrity sha512-Ux4ygGWsu2c7isFWe8Yu1YluJmqVhxqK2cLXNQA5AcC3QfbGNpM7fu0Y8b/z16pXLnFxZYvWhd3fhBY9DLmC6Q== 252 | -------------------------------------------------------------------------------- /src/RosMaster.ts: -------------------------------------------------------------------------------- 1 | import { HttpServer, XmlRpcServer, XmlRpcValue } from "@foxglove/xmlrpc"; 2 | 3 | import { LoggerService } from "./LoggerService"; 4 | import { RosFollowerClient } from "./RosFollowerClient"; 5 | import { RosXmlRpcResponse } from "./XmlRpcTypes"; 6 | import { isPlainObject } from "./objectTests"; 7 | 8 | function CheckArguments(args: XmlRpcValue[], expected: string[]): Error | undefined { 9 | if (args.length !== expected.length) { 10 | return new Error(`Expected ${expected.length} arguments, got ${args.length}`); 11 | } 12 | 13 | for (let i = 0; i < args.length; i++) { 14 | if (expected[i] !== "*" && typeof args[i] !== expected[i]) { 15 | return new Error(`Expected "${expected[i]}" for arg ${i}, got "${typeof args[i]}"`); 16 | } 17 | } 18 | 19 | return undefined; 20 | } 21 | 22 | // A server implementing the and 23 | // APIs. This can be used as 24 | // an alternative server implementation than roscore provided by the ros_comm 25 | // library. 26 | export class RosMaster { 27 | private _server: XmlRpcServer; 28 | private _log?: LoggerService; 29 | private _url?: string; 30 | 31 | private _nodes = new Map(); 32 | private _services = new Map>(); 33 | private _topics = new Map(); 34 | private _publications = new Map>(); 35 | private _subscriptions = new Map>(); 36 | 37 | private _parameters = new Map(); 38 | private _paramSubscriptions = new Map>(); 39 | 40 | constructor(httpServer: HttpServer, log?: LoggerService) { 41 | this._server = new XmlRpcServer(httpServer); 42 | this._log = log; 43 | } 44 | 45 | async start(hostname: string, port?: number): Promise { 46 | await this._server.listen(port, undefined, 10); 47 | this._url = `http://${hostname}:${this._server.port()}/`; 48 | 49 | this._server.setHandler("registerService", this.registerService); 50 | this._server.setHandler("unregisterService", this.unregisterService); 51 | this._server.setHandler("registerSubscriber", this.registerSubscriber); 52 | this._server.setHandler("unregisterSubscriber", this.unregisterSubscriber); 53 | this._server.setHandler("registerPublisher", this.registerPublisher); 54 | this._server.setHandler("unregisterPublisher", this.unregisterPublisher); 55 | this._server.setHandler("lookupNode", this.lookupNode); 56 | this._server.setHandler("getPublishedTopics", this.getPublishedTopics); 57 | this._server.setHandler("getTopicTypes", this.getTopicTypes); 58 | this._server.setHandler("getSystemState", this.getSystemState); 59 | this._server.setHandler("getUri", this.getUri); 60 | this._server.setHandler("lookupService", this.lookupService); 61 | this._server.setHandler("deleteParam", this.deleteParam); 62 | this._server.setHandler("setParam", this.setParam); 63 | this._server.setHandler("getParam", this.getParam); 64 | this._server.setHandler("searchParam", this.searchParam); 65 | this._server.setHandler("subscribeParam", this.subscribeParam); 66 | this._server.setHandler("unsubscribeParam", this.unsubscribeParam); 67 | this._server.setHandler("hasParam", this.hasParam); 68 | this._server.setHandler("getParamNames", this.getParamNames); 69 | } 70 | 71 | close(): void { 72 | this._server.close(); 73 | } 74 | 75 | url(): string | undefined { 76 | return this._url; 77 | } 78 | 79 | // handlers 80 | 81 | registerService = async ( 82 | _methodName: string, 83 | args: XmlRpcValue[], 84 | ): Promise => { 85 | // [callerId, service, serviceApi, callerApi] 86 | const err = CheckArguments(args, ["string", "string", "string", "string"]); 87 | if (err != null) { 88 | throw err; 89 | } 90 | 91 | const [callerId, service, serviceApi, callerApi] = args as [string, string, string, string]; 92 | 93 | if (!this._services.has(service)) { 94 | this._services.set(service, new Map()); 95 | } 96 | const serviceProviders = this._services.get(service) as Map; 97 | 98 | serviceProviders.set(callerId, serviceApi); 99 | this._nodes.set(callerId, callerApi); 100 | 101 | return [1, "", 0]; 102 | }; 103 | 104 | unregisterService = async ( 105 | _methodName: string, 106 | args: XmlRpcValue[], 107 | ): Promise => { 108 | // [callerId, service, serviceApi] 109 | const err = CheckArguments(args, ["string", "string", "string"]); 110 | if (err != null) { 111 | throw err; 112 | } 113 | 114 | const [callerId, service, _serviceApi] = args as [string, string, string]; 115 | const serviceProviders = this._services.get(service); 116 | if (serviceProviders == undefined) { 117 | return [1, "", 0]; 118 | } 119 | 120 | const removed = serviceProviders.delete(callerId); 121 | if (serviceProviders.size === 0) { 122 | this._services.delete(service); 123 | } 124 | 125 | return [1, "", removed ? 1 : 0]; 126 | }; 127 | 128 | registerSubscriber = async ( 129 | _methodName: string, 130 | args: XmlRpcValue[], 131 | ): Promise => { 132 | // [callerId, topic, topicType, callerApi] 133 | const err = CheckArguments(args, ["string", "string", "string", "string"]); 134 | if (err != null) { 135 | throw err; 136 | } 137 | 138 | const [callerId, topic, topicType, callerApi] = args as [string, string, string, string]; 139 | 140 | const dataType = this._topics.get(topic); 141 | if (dataType != undefined && dataType !== topicType) { 142 | return [0, `topic_type "${topicType}" for topic "${topic}" does not match "${dataType}"`, []]; 143 | } 144 | 145 | if (!this._subscriptions.has(topic)) { 146 | this._subscriptions.set(topic, new Set()); 147 | } 148 | const subscribers = this._subscriptions.get(topic) as Set; 149 | subscribers.add(callerId); 150 | 151 | this._nodes.set(callerId, callerApi); 152 | 153 | const publishers = Array.from((this._publications.get(topic) ?? new Set()).values()); 154 | const publisherApis = publishers 155 | .map((p) => this._nodes.get(p)) 156 | .filter((a) => a != undefined) as string[]; 157 | return [1, "", publisherApis]; 158 | }; 159 | 160 | unregisterSubscriber = async ( 161 | _methodName: string, 162 | args: XmlRpcValue[], 163 | ): Promise => { 164 | // [callerId, topic, callerApi] 165 | const err = CheckArguments(args, ["string", "string", "string"]); 166 | if (err != null) { 167 | throw err; 168 | } 169 | 170 | const [callerId, topic, _callerApi] = args as [string, string, string]; 171 | 172 | const subscribers = this._subscriptions.get(topic); 173 | if (subscribers == undefined) { 174 | return [1, "", 0]; 175 | } 176 | 177 | const removed = subscribers.delete(callerId); 178 | if (subscribers.size === 0) { 179 | this._subscriptions.delete(topic); 180 | } 181 | 182 | return [1, "", removed ? 1 : 0]; 183 | }; 184 | 185 | registerPublisher = async ( 186 | _methodName: string, 187 | args: XmlRpcValue[], 188 | ): Promise => { 189 | // [callerId, topic, topicType, callerApi] 190 | const err = CheckArguments(args, ["string", "string", "string", "string"]); 191 | if (err != null) { 192 | throw err; 193 | } 194 | 195 | const [callerId, topic, topicType, callerApi] = args as [string, string, string, string]; 196 | 197 | const dataType = this._topics.get(topic); 198 | if (dataType != undefined && dataType !== topicType) { 199 | return [0, `topic_type "${topicType}" for topic "${topic}" does not match "${dataType}"`, []]; 200 | } 201 | 202 | if (!this._publications.has(topic)) { 203 | this._publications.set(topic, new Set()); 204 | } 205 | const publishers = this._publications.get(topic) as Set; 206 | publishers.add(callerId); 207 | 208 | this._topics.set(topic, topicType); 209 | this._nodes.set(callerId, callerApi); 210 | 211 | const subscribers = Array.from((this._subscriptions.get(topic) ?? new Set()).values()); 212 | const subscriberApis = subscribers 213 | .map((s) => this._nodes.get(s)) 214 | .filter((a) => a != undefined) as string[]; 215 | 216 | // Inform all subscribers of the new publisher 217 | const publisherApis = Array.from(publishers.values()) 218 | .sort() 219 | .map((p) => this._nodes.get(p)) 220 | .filter((a) => a != undefined) as string[]; 221 | for (const api of subscriberApis) { 222 | new RosFollowerClient(api) 223 | .publisherUpdate(callerId, topic, publisherApis) 224 | .catch((apiErr) => this._log?.warn?.(`publisherUpdate call to ${api} failed: ${apiErr}`)); 225 | } 226 | 227 | return [1, "", subscriberApis]; 228 | }; 229 | 230 | unregisterPublisher = async ( 231 | _methodName: string, 232 | args: XmlRpcValue[], 233 | ): Promise => { 234 | // [callerId, topic, callerApi] 235 | const err = CheckArguments(args, ["string", "string", "string"]); 236 | if (err != null) { 237 | throw err; 238 | } 239 | 240 | const [callerId, topic, _callerApi] = args as [string, string, string]; 241 | 242 | const publishers = this._publications.get(topic); 243 | if (publishers == undefined) { 244 | return [1, "", 0]; 245 | } 246 | 247 | const removed = publishers.delete(callerId); 248 | if (publishers.size === 0) { 249 | this._publications.delete(topic); 250 | } 251 | 252 | return [1, "", removed ? 1 : 0]; 253 | }; 254 | 255 | lookupNode = async (_methodName: string, args: XmlRpcValue[]): Promise => { 256 | // [callerId, nodeName] 257 | const err = CheckArguments(args, ["string", "string"]); 258 | if (err != null) { 259 | throw err; 260 | } 261 | 262 | const [_callerId, nodeName] = args as [string, string]; 263 | 264 | const nodeApi = this._nodes.get(nodeName); 265 | if (nodeApi == undefined) { 266 | return [0, `node "${nodeName}" not found`, ""]; 267 | } 268 | return [1, "", nodeApi]; 269 | }; 270 | 271 | getPublishedTopics = async ( 272 | _methodName: string, 273 | args: XmlRpcValue[], 274 | ): Promise => { 275 | // [callerId, subgraph] 276 | const err = CheckArguments(args, ["string", "string"]); 277 | if (err != null) { 278 | throw err; 279 | } 280 | 281 | // Subgraph filtering would need to be supported to become a fully compatible implementation 282 | const [_callerId, _subgraph] = args as [string, string]; 283 | 284 | const entries: [string, string][] = []; 285 | for (const topic of this._publications.keys()) { 286 | const dataType = this._topics.get(topic); 287 | if (dataType != undefined) { 288 | entries.push([topic, dataType]); 289 | } 290 | } 291 | 292 | return [1, "", entries]; 293 | }; 294 | 295 | getTopicTypes = async (_methodName: string, args: XmlRpcValue[]): Promise => { 296 | // [callerId] 297 | const err = CheckArguments(args, ["string"]); 298 | if (err != null) { 299 | throw err; 300 | } 301 | 302 | const entries = Array.from(this._topics.entries()); 303 | return [1, "", entries]; 304 | }; 305 | 306 | getSystemState = async (_methodName: string, args: XmlRpcValue[]): Promise => { 307 | // [callerId] 308 | const err = CheckArguments(args, ["string"]); 309 | if (err != null) { 310 | throw err; 311 | } 312 | 313 | const publishers: [string, string[]][] = Array.from(this._publications.entries()).map( 314 | ([topic, nodeNames]) => [topic, Array.from(nodeNames.values()).sort()], 315 | ); 316 | 317 | const subscribers: [string, string[]][] = Array.from(this._subscriptions.entries()).map( 318 | ([topic, nodeNames]) => [topic, Array.from(nodeNames.values()).sort()], 319 | ); 320 | 321 | const services: [string, string[]][] = Array.from(this._services.entries()).map( 322 | ([service, nodeNamesToServiceApis]) => [ 323 | service, 324 | Array.from(nodeNamesToServiceApis.keys()).sort(), 325 | ], 326 | ); 327 | 328 | return [1, "", [publishers, subscribers, services]]; 329 | }; 330 | 331 | getUri = async (_methodName: string, args: XmlRpcValue[]): Promise => { 332 | // [callerId] 333 | const err = CheckArguments(args, ["string"]); 334 | if (err != null) { 335 | throw err; 336 | } 337 | 338 | const url = this._url; 339 | if (url == undefined) { 340 | return [0, "", "not running"]; 341 | } 342 | 343 | return [1, "", url]; 344 | }; 345 | 346 | lookupService = async (_methodName: string, args: XmlRpcValue[]): Promise => { 347 | // [callerId, service] 348 | const err = CheckArguments(args, ["string", "string"]); 349 | if (err != null) { 350 | throw err; 351 | } 352 | 353 | const [_callerId, service] = args as [string, string]; 354 | 355 | const serviceProviders = this._services.get(service); 356 | if (serviceProviders == undefined || serviceProviders.size === 0) { 357 | return [0, `no providers for service "${service}"`, ""]; 358 | } 359 | 360 | const serviceUrl = serviceProviders.values().next().value as string; 361 | return [1, "", serviceUrl]; 362 | }; 363 | 364 | // handlers 365 | 366 | deleteParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 367 | // [callerId, key] 368 | const err = CheckArguments(args, ["string", "string"]); 369 | if (err != null) { 370 | throw err; 371 | } 372 | 373 | const [_callerId, key] = args as [string, string]; 374 | 375 | this._parameters.delete(key); 376 | 377 | return [1, "", 0]; 378 | }; 379 | 380 | setParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 381 | // [callerId, key, value] 382 | const err = CheckArguments(args, ["string", "string", "*"]); 383 | if (err != null) { 384 | throw err; 385 | } 386 | 387 | const [callerId, key, value] = args as [string, string, XmlRpcValue]; 388 | const allKeyValues: [string, XmlRpcValue][] = isPlainObject(value) 389 | ? objectToKeyValues(key, value as Record) 390 | : [[key, value]]; 391 | 392 | for (const [curKey, curValue] of allKeyValues) { 393 | this._parameters.set(curKey, curValue); 394 | 395 | // Notify any parameter subscribers about this new value 396 | const subscribers = this._paramSubscriptions.get(curKey); 397 | if (subscribers != undefined) { 398 | for (const api of subscribers.values()) { 399 | new RosFollowerClient(api) 400 | .paramUpdate(callerId, curKey, curValue) 401 | .catch((apiErr) => this._log?.warn?.(`paramUpdate call to ${api} failed: ${apiErr}`)); 402 | } 403 | } 404 | } 405 | 406 | return [1, "", 0]; 407 | }; 408 | 409 | getParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 410 | // [callerId, key] 411 | const err = CheckArguments(args, ["string", "string"]); 412 | if (err != null) { 413 | throw err; 414 | } 415 | 416 | // This endpoint needs to support namespace retrieval to fully match the rosparam server 417 | // behavior 418 | const [_callerId, key] = args as [string, string]; 419 | 420 | const value = this._parameters.get(key); 421 | const status = value != undefined ? 1 : 0; 422 | return [status, "", value ?? {}]; 423 | }; 424 | 425 | searchParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 426 | // [callerId, key] 427 | const err = CheckArguments(args, ["string", "string"]); 428 | if (err != null) { 429 | throw err; 430 | } 431 | 432 | // This endpoint would have to take into account the callerId namespace, partial matching, and 433 | // returning undefined keys to fully match the rosparam server behavior 434 | const [_callerId, key] = args as [string, string]; 435 | 436 | const value = this._parameters.get(key); 437 | const status = value != undefined ? 1 : 0; 438 | return [status, "", value ?? {}]; 439 | }; 440 | 441 | subscribeParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 442 | // [callerId, callerApi, key] 443 | const err = CheckArguments(args, ["string", "string", "string"]); 444 | if (err != null) { 445 | throw err; 446 | } 447 | 448 | const [callerId, callerApi, key] = args as [string, string, string]; 449 | 450 | if (!this._paramSubscriptions.has(key)) { 451 | this._paramSubscriptions.set(key, new Map()); 452 | } 453 | const subscriptions = this._paramSubscriptions.get(key) as Map; 454 | 455 | subscriptions.set(callerId, callerApi); 456 | 457 | const value = this._parameters.get(key) ?? {}; 458 | return [1, "", value]; 459 | }; 460 | 461 | unsubscribeParam = async ( 462 | _methodName: string, 463 | args: XmlRpcValue[], 464 | ): Promise => { 465 | // [callerId, callerApi, key] 466 | const err = CheckArguments(args, ["string", "string", "string"]); 467 | if (err != null) { 468 | throw err; 469 | } 470 | 471 | const [callerId, _callerApi, key] = args as [string, string, string]; 472 | 473 | const subscriptions = this._paramSubscriptions.get(key); 474 | if (subscriptions == undefined) { 475 | return [1, "", 0]; 476 | } 477 | 478 | const removed = subscriptions.delete(callerId); 479 | return [1, "", removed ? 1 : 0]; 480 | }; 481 | 482 | hasParam = async (_methodName: string, args: XmlRpcValue[]): Promise => { 483 | // [callerId, key] 484 | const err = CheckArguments(args, ["string", "string"]); 485 | if (err != null) { 486 | throw err; 487 | } 488 | 489 | const [_callerId, key] = args as [string, string]; 490 | return [1, "", this._parameters.has(key)]; 491 | }; 492 | 493 | getParamNames = async (_methodName: string, args: XmlRpcValue[]): Promise => { 494 | // [callerId] 495 | const err = CheckArguments(args, ["string"]); 496 | if (err != null) { 497 | throw err; 498 | } 499 | 500 | const keys = Array.from(this._parameters.keys()).sort(); 501 | return [1, "", keys]; 502 | }; 503 | } 504 | 505 | function objectToKeyValues( 506 | prefix: string, 507 | object: Record, 508 | ): [string, XmlRpcValue][] { 509 | let entries: [string, XmlRpcValue][] = []; 510 | for (const curKey in object) { 511 | const key = `${prefix}/${curKey}`; 512 | const value = object[curKey]; 513 | if (isPlainObject(value)) { 514 | entries = entries.concat(objectToKeyValues(key, value as Record)); 515 | } else { 516 | entries.push([key, value]); 517 | } 518 | } 519 | return entries; 520 | } 521 | -------------------------------------------------------------------------------- /src/RosNode.ts: -------------------------------------------------------------------------------- 1 | import { MessageDefinition } from "@foxglove/message-definition"; 2 | import { 3 | parse as parseMessageDefinition, 4 | md5 as rosMsgMd5sum, 5 | stringify as rosMsgDefinitionText, 6 | } from "@foxglove/rosmsg"; 7 | import { MessageWriter } from "@foxglove/rosmsg-serialization"; 8 | import { HttpServer, XmlRpcFault, XmlRpcValue } from "@foxglove/xmlrpc"; 9 | import { EventEmitter } from "eventemitter3"; 10 | 11 | import { Client } from "./Client"; 12 | import { LoggerService } from "./LoggerService"; 13 | import { Publication } from "./Publication"; 14 | import { RosFollower } from "./RosFollower"; 15 | import { RosFollowerClient } from "./RosFollowerClient"; 16 | import { RosMasterClient } from "./RosMasterClient"; 17 | import { RosParamClient } from "./RosParamClient"; 18 | import { Subscription } from "./Subscription"; 19 | import { TcpConnection } from "./TcpConnection"; 20 | import { TcpPublisher } from "./TcpPublisher"; 21 | import { TcpSocketCreate, TcpServer, TcpAddress, NetworkInterface } from "./TcpTypes"; 22 | import { RosXmlRpcResponse } from "./XmlRpcTypes"; 23 | import { retryForever } from "./backoff"; 24 | import { difference } from "./difference"; 25 | import { isEmptyPlainObject } from "./objectTests"; 26 | 27 | export type RosGraph = { 28 | publishers: Map>; // Maps topic names to arrays of nodes publishing each topic 29 | subscribers: Map>; // Maps topic names to arrays of nodes subscribing to each topic 30 | services: Map>; // Maps service names to arrays of nodes providing each service 31 | }; 32 | 33 | export type SubscribeOpts = { 34 | topic: string; 35 | dataType: string; 36 | md5sum?: string; 37 | tcpNoDelay?: boolean; 38 | }; 39 | 40 | export type PublishOpts = { 41 | topic: string; 42 | dataType: string; 43 | latching?: boolean; 44 | messageDefinition?: MessageDefinition[]; 45 | messageDefinitionText?: string; 46 | md5sum?: string; 47 | }; 48 | 49 | export type ParamUpdateArgs = { 50 | key: string; 51 | value: XmlRpcValue; 52 | prevValue: XmlRpcValue; 53 | callerId: string; 54 | }; 55 | 56 | export type PublisherUpdateArgs = { 57 | topic: string; 58 | publishers: string[]; 59 | prevPublishers: string[]; 60 | callerId: string; 61 | }; 62 | 63 | const OK = 1; 64 | 65 | export interface RosNodeEvents { 66 | paramUpdate: (args: ParamUpdateArgs) => void; 67 | publisherUpdate: (args: PublisherUpdateArgs) => void; 68 | error: (err: Error) => void; 69 | } 70 | 71 | export class RosNode extends EventEmitter { 72 | readonly name: string; 73 | readonly hostname: string; 74 | readonly pid: number; 75 | 76 | rosMasterClient: RosMasterClient; 77 | rosParamClient: RosParamClient; 78 | rosFollower: RosFollower; 79 | subscriptions = new Map(); 80 | publications = new Map(); 81 | parameters = new Map(); 82 | 83 | private _running = true; 84 | private _tcpSocketCreate: TcpSocketCreate; 85 | private _connectionIdCounter = 0; 86 | private _tcpPublisher?: TcpPublisher; 87 | private _localApiUrl?: string; 88 | private _log?: LoggerService; 89 | 90 | constructor(options: { 91 | name: string; 92 | hostname: string; 93 | pid: number; 94 | rosMasterUri: string; 95 | httpServer: HttpServer; 96 | tcpSocketCreate: TcpSocketCreate; 97 | tcpServer?: TcpServer; 98 | log?: LoggerService; 99 | }) { 100 | super(); 101 | this.name = options.name; 102 | this.hostname = options.hostname; 103 | this.pid = options.pid; 104 | this.rosMasterClient = new RosMasterClient(options.rosMasterUri); 105 | this.rosParamClient = new RosParamClient(options.rosMasterUri); 106 | this.rosFollower = new RosFollower(this, options.httpServer); 107 | this._tcpSocketCreate = options.tcpSocketCreate; 108 | if (options.tcpServer != undefined) { 109 | this._tcpPublisher = new TcpPublisher({ 110 | server: options.tcpServer, 111 | nodeName: this.name, 112 | getConnectionId: this._newConnectionId, 113 | getPublication: this._getPublication, 114 | log: options.log, 115 | }); 116 | this._tcpPublisher.on("connection", this._handleTcpClientConnection); 117 | this._tcpPublisher.on("error", this._handleTcpPublisherError); 118 | } 119 | this._log = options.log; 120 | 121 | this.rosFollower.on("paramUpdate", this._handleParamUpdate); 122 | this.rosFollower.on("publisherUpdate", this._handlePublisherUpdate); 123 | } 124 | 125 | async start(port?: number): Promise { 126 | return await this.rosFollower 127 | .start(this.hostname, port) 128 | .then(() => this._log?.debug?.(`rosfollower listening at ${this.rosFollower.url()}`)); 129 | } 130 | 131 | shutdown(_msg?: string): void { 132 | this._log?.debug?.("shutting down"); 133 | this._running = false; 134 | this._tcpPublisher?.close(); 135 | this.rosFollower.close(); 136 | 137 | if (this.parameters.size > 0) { 138 | this.unsubscribeAllParams().catch((unk) => { 139 | const err = unk instanceof Error ? unk : new Error(unk as string); 140 | this._log?.warn?.(err.message, "shutdown"); 141 | this.emit("error", err); 142 | }); 143 | } 144 | 145 | for (const subTopic of Array.from(this.subscriptions.keys())) { 146 | this.unsubscribe(subTopic); 147 | } 148 | 149 | for (const pubTopic of Array.from(this.publications.keys())) { 150 | this.unadvertise(pubTopic); 151 | } 152 | 153 | this.subscriptions.clear(); 154 | this.publications.clear(); 155 | this.parameters.clear(); 156 | } 157 | 158 | subscribe(options: SubscribeOpts): Subscription { 159 | const { topic, dataType } = options; 160 | const md5sum = options.md5sum ?? "*"; 161 | const tcpNoDelay = options.tcpNoDelay ?? false; 162 | 163 | // Check if we are already subscribed 164 | let subscription = this.subscriptions.get(topic); 165 | if (subscription != undefined) { 166 | this._log?.debug?.(`reusing existing subscribtion to ${topic} (${dataType})`); 167 | return subscription; 168 | } 169 | 170 | subscription = new Subscription({ name: topic, md5sum, dataType, tcpNoDelay }); 171 | this.subscriptions.set(topic, subscription); 172 | 173 | this._log?.debug?.(`subscribing to ${topic} (${dataType})`); 174 | 175 | // Asynchronously register this subscription with rosmaster and connect to 176 | // each publisher 177 | this._registerSubscriberAndConnect(subscription).catch((err) => { 178 | // This should never be called, this._registerSubscriberAndConnect() is not expected to throw 179 | this._log?.warn?.( 180 | `subscribe registration and connection unexpectedly failed: ${err}`, 181 | "subscribe", 182 | ); 183 | }); 184 | 185 | return subscription; 186 | } 187 | 188 | async advertise(options: PublishOpts): Promise { 189 | const { topic, dataType } = options; 190 | 191 | const addr = await this.tcpServerAddress(); 192 | if (addr == undefined) { 193 | throw new Error(`Cannot publish ${topic} without a listening tcpServer`); 194 | } 195 | 196 | // Check if we are already publishing 197 | let publication = this.publications.get(topic); 198 | if (publication != undefined) { 199 | this._log?.debug?.(`reusing existing publication for ${topic} (${dataType})`); 200 | return publication; 201 | } 202 | 203 | const messageDefinition = 204 | options.messageDefinition ?? parseMessageDefinition(options.messageDefinitionText ?? ""); 205 | const canonicalMsgDefText = rosMsgDefinitionText(messageDefinition); 206 | const messageDefinitionText = options.messageDefinitionText ?? canonicalMsgDefText; 207 | const md5sum = options.md5sum ?? rosMsgMd5sum(messageDefinition); 208 | const messageWriter = new MessageWriter(messageDefinition); 209 | 210 | publication = new Publication( 211 | topic, 212 | md5sum, 213 | dataType, 214 | options.latching ?? false, 215 | messageDefinition, 216 | messageDefinitionText, 217 | messageWriter, 218 | ); 219 | this.publications.set(topic, publication); 220 | 221 | this._log?.debug?.(`publishing ${topic} (${dataType})`); 222 | 223 | // Register with with rosmaster as a publisher for the requested topic. If 224 | // this request fails, an exception is thrown 225 | const subscribers = await this._registerPublisher(publication); 226 | 227 | this._log?.info?.( 228 | `registered as a publisher for ${topic}, ${subscribers.length} current subscriber(s)`, 229 | ); 230 | 231 | return publication; 232 | } 233 | 234 | async publish(topic: string, message: unknown): Promise { 235 | if (this._tcpPublisher == undefined) { 236 | throw new Error(`Cannot publish without a tcpServer`); 237 | } 238 | 239 | const publication = this.publications.get(topic); 240 | if (publication == undefined) { 241 | throw new Error(`Cannot publish to unadvertised topic "${topic}"`); 242 | } 243 | 244 | return await this._tcpPublisher.publish(publication, message); 245 | } 246 | 247 | isSubscribedTo(topic: string): boolean { 248 | return this._running && this.subscriptions.has(topic); 249 | } 250 | 251 | isAdvertising(topic: string): boolean { 252 | return this._running && this.publications.has(topic); 253 | } 254 | 255 | unsubscribe(topic: string): boolean { 256 | const subscription = this.subscriptions.get(topic); 257 | if (subscription == null) { 258 | return false; 259 | } 260 | 261 | this._unregisterSubscriber(topic).catch((err) => { 262 | // This should never happen 263 | this._log?.warn?.(`unregisterSubscriber failed for ${topic}: ${err}`); 264 | }); 265 | 266 | subscription.close(); 267 | this.subscriptions.delete(topic); 268 | return true; 269 | } 270 | 271 | unadvertise(topic: string): boolean { 272 | const publication = this.publications.get(topic); 273 | if (publication == null) { 274 | return false; 275 | } 276 | 277 | this._unregisterPublisher(topic).catch((err) => { 278 | // This should never happen 279 | this._log?.warn?.(`_unregisterPublisher failed for ${topic}: ${err}`); 280 | }); 281 | 282 | publication.close(); 283 | this.publications.delete(topic); 284 | return true; 285 | } 286 | 287 | async getParamNames(): Promise { 288 | const [status, msg, names] = await this.rosParamClient.getParamNames(this.name); 289 | if (status !== OK) { 290 | throw new Error(`getParamNames returned failure (status=${status}): ${msg}`); 291 | } 292 | if (!Array.isArray(names)) { 293 | throw new Error(`getParamNames returned unrecognized data (${msg})`); 294 | } 295 | return names as string[]; 296 | } 297 | 298 | async setParameter(key: string, value: XmlRpcValue): Promise { 299 | const [status, msg] = await this.rosParamClient.setParam(this.name, key, value); 300 | if (status !== OK) { 301 | throw new Error(`setParam returned failure (status=${status}): ${msg}`); 302 | } 303 | 304 | // Also do a local update because ROS param server won't notify us if 305 | // we initiated the parameter update. 306 | this._handleParamUpdate(key, value, this.name); 307 | } 308 | 309 | async subscribeParam(key: string): Promise { 310 | const callerApi = this._callerApi(); 311 | const [status, msg, value] = await this.rosParamClient.subscribeParam( 312 | this.name, 313 | callerApi, 314 | key, 315 | ); 316 | if (status !== OK) { 317 | throw new Error(`subscribeParam returned failure (status=${status}): ${msg}`); 318 | } 319 | // rosparam server returns an empty object ({}) if the parameter has not been set yet 320 | const adjustedValue = isEmptyPlainObject(value) ? undefined : value; 321 | this.parameters.set(key, adjustedValue); 322 | 323 | this._log?.debug?.(`subscribed ${callerApi} to param "${key}" (${String(adjustedValue)})`); 324 | return adjustedValue; 325 | } 326 | 327 | async unsubscribeParam(key: string): Promise { 328 | const callerApi = this._callerApi(); 329 | const [status, msg, value] = await this.rosParamClient.unsubscribeParam( 330 | this.name, 331 | callerApi, 332 | key, 333 | ); 334 | if (status !== OK) { 335 | throw new Error(`unsubscribeParam returned failure (status=${status}): ${msg}`); 336 | } 337 | this.parameters.delete(key); 338 | const didUnsubscribe = (value as number) === 1; 339 | 340 | this._log?.debug?.( 341 | `unsubscribed ${callerApi} from param "${key}" (didUnsubscribe=${didUnsubscribe})`, 342 | ); 343 | return didUnsubscribe; 344 | } 345 | 346 | async subscribeAllParams(): Promise>> { 347 | let keys = await this.getParamNames(); 348 | const curKeys = Array.from(this.parameters.keys()); 349 | const callerApi = this._callerApi(); 350 | 351 | // Remove any local parameters the rosparam server didn't return 352 | const removedKeys = difference(curKeys, keys); 353 | if (removedKeys.length > 0) { 354 | this._log?.debug?.(`removing missing parameters ${JSON.stringify(removedKeys)}`); 355 | for (const key of removedKeys) { 356 | this.parameters.delete(key); 357 | } 358 | } 359 | 360 | // Check if there are any parameters we don't already have locally 361 | keys = difference(keys, curKeys); 362 | if (keys.length === 0) { 363 | return this.parameters; 364 | } 365 | 366 | const res = await this.rosParamClient.subscribeParams(this.name, callerApi, keys); 367 | if (res.length !== keys.length) { 368 | throw new Error( 369 | `subscribeAllParams returned ${res.length} entries, expected ${ 370 | keys.length 371 | }: ${JSON.stringify(res)}`, 372 | ); 373 | } 374 | 375 | // Update the local map of all subscribed parameters 376 | for (let i = 0; i < keys.length; i++) { 377 | const key = keys[i] as string; 378 | const entry = res[i]; 379 | if (entry instanceof XmlRpcFault) { 380 | this._log?.warn?.(`subscribeAllParams faulted on "${key}" (${entry})`); 381 | this.emit("error", new Error(`subscribeAllParams faulted on "${key}" (${entry})`)); 382 | continue; 383 | } 384 | const [status, msg, value] = entry as RosXmlRpcResponse; 385 | if (status !== OK) { 386 | this._log?.warn?.(`subscribeAllParams not ok for "${key}" (status=${status}): ${msg}`); 387 | this.emit( 388 | "error", 389 | new Error(`subscribeAllParams not ok for "${key}" (status=${status}): ${msg}`), 390 | ); 391 | continue; 392 | } 393 | // rosparam server returns an empty object ({}) if the parameter has not been set yet 394 | const adjustedValue = isEmptyPlainObject(value) ? undefined : value; 395 | this.parameters.set(key, adjustedValue); 396 | } 397 | 398 | this._log?.debug?.(`subscribed ${callerApi} to parameters (${keys})`); 399 | return this.parameters; 400 | } 401 | 402 | async unsubscribeAllParams(): Promise { 403 | const keys = Array.from(this.parameters.keys()); 404 | const callerApi = this._callerApi(); 405 | const res = await this.rosParamClient.unsubscribeParams(this.name, callerApi, keys); 406 | if (res.length !== keys.length) { 407 | throw new Error(`unsubscribeAllParams returned unrecognized data: ${JSON.stringify(res)}`); 408 | } 409 | for (let i = 0; i < keys.length; i++) { 410 | const key = keys[i]!; 411 | const [status, msg] = res[i] as RosXmlRpcResponse; 412 | if (status !== OK) { 413 | this._log?.warn?.(`unsubscribeAllParams failed for "${key}" (status=${status}): ${msg}`); 414 | this.emit( 415 | "error", 416 | new Error(`unsubscribeAllParams failed for "${key}" (status=${status}): ${msg}`), 417 | ); 418 | continue; 419 | } 420 | } 421 | 422 | this._log?.debug?.(`unsubscribed ${callerApi} from all parameters (${String(keys)})`); 423 | this.parameters.clear(); 424 | } 425 | 426 | async getPublishedTopics(subgraph?: string): Promise<[topic: string, dataType: string][]> { 427 | const [status, msg, topicsAndTypes] = await this.rosMasterClient.getPublishedTopics( 428 | this.name, 429 | subgraph, 430 | ); 431 | if (status !== OK) { 432 | throw new Error(`getPublishedTopics returned failure (status=${status}): ${msg}`); 433 | } 434 | return topicsAndTypes as [string, string][]; 435 | } 436 | 437 | async getSystemState(): Promise { 438 | const [status, msg, systemState] = await this.rosMasterClient.getSystemState(this.name); 439 | if (status !== OK) { 440 | throw new Error(`getPublishedTopics returned failure (status=${status}): ${msg}`); 441 | } 442 | if (!Array.isArray(systemState) || systemState.length !== 3) { 443 | throw new Error(`getPublishedTopics returned unrecognized data (${msg})`); 444 | } 445 | 446 | // Each of these has the form [ [topic, [node1...nodeN]] ... ] 447 | type SystemStateEntry = [topic: string, nodes: string[]]; 448 | type SystemStateResponse = [SystemStateEntry[], SystemStateEntry[], SystemStateEntry[]]; 449 | const [pubs, subs, srvs] = systemState as SystemStateResponse; 450 | 451 | const createMap = (entries: SystemStateEntry[]) => 452 | new Map>(entries.map(([topic, nodes]) => [topic, new Set(nodes)])); 453 | 454 | return { 455 | publishers: createMap(pubs), 456 | subscribers: createMap(subs), 457 | services: createMap(srvs), 458 | }; 459 | } 460 | 461 | async tcpServerAddress(): Promise { 462 | return await this._tcpPublisher?.address(); 463 | } 464 | 465 | receivedBytes(): number { 466 | let bytes = 0; 467 | for (const sub of this.subscriptions.values()) { 468 | bytes += sub.receivedBytes(); 469 | } 470 | return bytes; 471 | } 472 | 473 | static async RequestTopic( 474 | name: string, 475 | topic: string, 476 | apiClient: RosFollowerClient, 477 | ): Promise<{ address: string; port: number }> { 478 | let res: RosXmlRpcResponse; 479 | try { 480 | res = await apiClient.requestTopic(name, topic, [["TCPROS"]]); 481 | } catch (err) { 482 | throw new Error(`requestTopic("${topic}") from ${apiClient.url()} failed. err=${err}`); 483 | } 484 | const [status, msg, protocol] = res; 485 | 486 | if (status !== OK) { 487 | throw new Error( 488 | `requestTopic("${topic}") from ${apiClient.url()} failed. status=${status}, msg=${msg}`, 489 | ); 490 | } 491 | if (!Array.isArray(protocol) || protocol.length < 3 || protocol[0] !== "TCPROS") { 492 | throw new Error(`TCP not supported by ${apiClient.url()} for topic "${topic}"`); 493 | } 494 | 495 | return { port: protocol[2] as number, address: protocol[1] as string }; 496 | } 497 | 498 | private _newConnectionId = (): number => { 499 | return this._connectionIdCounter++; 500 | }; 501 | 502 | private _getPublication = (topic: string): Publication | undefined => { 503 | return this.publications.get(topic); 504 | }; 505 | 506 | private _callerApi(): string { 507 | if (this._localApiUrl != undefined) { 508 | return this._localApiUrl; 509 | } 510 | 511 | this._localApiUrl = this.rosFollower.url(); 512 | if (this._localApiUrl == undefined) { 513 | throw new Error("Local XMLRPC server was not started"); 514 | } 515 | 516 | return this._localApiUrl; 517 | } 518 | 519 | private _handleParamUpdate = (key: string, value: XmlRpcValue, callerId: string) => { 520 | const prevValue = this.parameters.get(key); 521 | this.parameters.set(key, value); 522 | this.emit("paramUpdate", { key, value, prevValue, callerId }); 523 | }; 524 | 525 | private _handlePublisherUpdate = (topic: string, publishers: string[], callerId: string) => { 526 | const sub = this.subscriptions.get(topic); 527 | if (sub == undefined) { 528 | return; 529 | } 530 | 531 | const prevPublishers = Array.from(sub.publishers().values()).map((v) => v.publisherXmlRpcUrl()); 532 | const removed = difference(prevPublishers, publishers); 533 | const added = difference(publishers, prevPublishers); 534 | 535 | // Remove all publishers that have disappeared 536 | for (const removePub of removed) { 537 | for (const [connectionId, pub] of sub.publishers().entries()) { 538 | if (pub.publisherXmlRpcUrl() === removePub) { 539 | this._log?.info?.(`publisher ${removePub} for ${sub.name} went offline, disconnecting`); 540 | sub.removePublisher(connectionId); 541 | break; 542 | } 543 | } 544 | } 545 | 546 | // Add any new publishers that have appeared 547 | for (const addPub of added) { 548 | this._log?.info?.(`publisher ${addPub} for ${sub.name} came online, connecting`); 549 | this._subscribeToPublisher(addPub, sub).catch((err) => { 550 | // This should never be called, this._subscribeToPublisher() is not expected to throw 551 | this._log?.warn?.(`subscribe to publisher unexpectedly failed: ${err}`); 552 | }); 553 | } 554 | 555 | this.emit("publisherUpdate", { topic, publishers, prevPublishers, callerId }); 556 | }; 557 | 558 | private _handleTcpClientConnection = ( 559 | topic: string, 560 | connectionId: number, 561 | destinationCallerId: string, 562 | client: Client, 563 | ) => { 564 | const publication = this.publications.get(topic); 565 | if (publication == undefined) { 566 | this._log?.warn?.(`${client.toString()} connected to non-published topic ${topic}`); 567 | this.emit( 568 | "error", 569 | new Error(`${client.toString()} connected to non-published topic ${topic}`), 570 | ); 571 | return client.close(); 572 | } 573 | 574 | this._log?.info?.( 575 | `adding subscriber ${client.toString()} (${destinationCallerId}) to topic ${topic}, connectionId ${connectionId}`, 576 | ); 577 | publication.addSubscriber(connectionId, destinationCallerId, client); 578 | }; 579 | 580 | private _handleTcpPublisherError = (err: Error) => { 581 | this.emit("error", err); 582 | }; 583 | 584 | private async _registerSubscriber(subscription: Subscription): Promise { 585 | if (!this._running) { 586 | return []; 587 | } 588 | 589 | const callerApi = this._callerApi(); 590 | 591 | // Register with rosmaster as a subscriber to this topic 592 | const [status, msg, publishers] = await this.rosMasterClient.registerSubscriber( 593 | this.name, 594 | subscription.name, 595 | subscription.dataType, 596 | callerApi, 597 | ); 598 | 599 | if (status !== OK) { 600 | throw new Error(`registerSubscriber() failed. status=${status}, msg="${msg}"`); 601 | } 602 | 603 | if (!Array.isArray(publishers)) { 604 | throw new Error( 605 | `registerSubscriber() did not receive a list of publishers. value=${publishers}`, 606 | ); 607 | } 608 | 609 | this._log?.debug?.(`registered subscriber to ${subscription.name} (${subscription.dataType})`); 610 | return publishers as string[]; 611 | } 612 | 613 | private async _registerPublisher(publication: Publication): Promise { 614 | if (!this._running) { 615 | return []; 616 | } 617 | 618 | const callerApi = this._callerApi(); 619 | 620 | const [status, msg, subscribers] = await this.rosMasterClient.registerPublisher( 621 | this.name, 622 | publication.name, 623 | publication.dataType, 624 | callerApi, 625 | ); 626 | 627 | if (status !== OK) { 628 | throw new Error(`registerPublisher() failed. status=${status}, msg="${msg}"`); 629 | } 630 | 631 | this._log?.debug?.(`registered publisher for ${publication.name} (${publication.dataType})`); 632 | if (!Array.isArray(subscribers)) { 633 | throw new Error( 634 | `registerPublisher() did not receive a list of subscribers. value=${String(subscribers)}`, 635 | ); 636 | } 637 | 638 | return subscribers as string[]; 639 | } 640 | 641 | private async _unregisterSubscriber(topic: string): Promise { 642 | try { 643 | const callerApi = this._callerApi(); 644 | 645 | // Unregister with rosmaster as a subscriber to this topic 646 | const [status, msg] = await this.rosMasterClient.unregisterSubscriber( 647 | this.name, 648 | topic, 649 | callerApi, 650 | ); 651 | 652 | if (status !== OK) { 653 | throw new Error(`unregisterSubscriber() failed. status=${status}, msg="${msg}"`); 654 | } 655 | 656 | this._log?.debug?.(`unregistered subscriber to ${topic}`); 657 | } catch (unk) { 658 | // Warn and carry on, the rosmaster graph will be out of sync but there's 659 | // not much we can do (it may already be offline) 660 | const err = unk instanceof Error ? unk : new Error(unk as string); 661 | this._log?.warn?.(err.message, "unregisterSubscriber"); 662 | this.emit("error", err); 663 | } 664 | } 665 | 666 | private async _unregisterPublisher(topic: string): Promise { 667 | try { 668 | const callerApi = this._callerApi(); 669 | 670 | // Unregister with rosmaster as a publisher of this topic 671 | const [status, msg] = await this.rosMasterClient.unregisterPublisher( 672 | this.name, 673 | topic, 674 | callerApi, 675 | ); 676 | 677 | if (status !== OK) { 678 | throw new Error(`unregisterPublisher() failed. status=${status}, msg="${msg}"`); 679 | } 680 | 681 | this._log?.debug?.(`unregistered publisher for ${topic}`); 682 | } catch (unk) { 683 | // Warn and carry on, the rosmaster graph will be out of sync but there's 684 | // not much we can do (it may already be offline) 685 | const err = unk instanceof Error ? unk : new Error(unk as string); 686 | this._log?.warn?.(err.message, "unregisterPublisher"); 687 | this.emit("error", err); 688 | } 689 | } 690 | 691 | private async _registerSubscriberAndConnect(subscription: Subscription): Promise { 692 | // Register with rosmaster as a subscriber to the requested topic. Continue 693 | // retrying until the XML-RPC call to roscore succeeds, or we are no longer 694 | // subscribed 695 | const publishers = await retryForever(async () => { 696 | if (!this.isSubscribedTo(subscription.name)) { 697 | return []; 698 | } 699 | return await this._registerSubscriber(subscription); 700 | }); 701 | 702 | // Register with each publisher. Any failures communicating with individual node XML-RPC servers 703 | // or TCP sockets will be caught and retried 704 | await Promise.allSettled( 705 | publishers.map(async (pubUrl) => await this._subscribeToPublisher(pubUrl, subscription)), 706 | ); 707 | } 708 | 709 | async _subscribeToPublisher(pubUrl: string, subscription: Subscription): Promise { 710 | const topic = subscription.name; 711 | const dataType = subscription.dataType; 712 | const md5sum = subscription.md5sum; 713 | const tcpNoDelay = subscription.tcpNoDelay; 714 | 715 | if (!this.isSubscribedTo(topic)) { 716 | return; 717 | } 718 | 719 | let connection: TcpConnection; 720 | let address: string; 721 | let port: number; 722 | 723 | try { 724 | // Create an XMLRPC client to talk to this publisher 725 | const rosFollowerClient = new RosFollowerClient(pubUrl); 726 | 727 | // Call requestTopic on this publisher to register ourselves as a subscriber 728 | const socketInfo = await RosNode.RequestTopic(this.name, topic, rosFollowerClient); 729 | ({ address, port } = socketInfo); 730 | const uri = TcpConnection.Uri(address, port); 731 | this._log?.debug?.( 732 | `registered with ${pubUrl} as a subscriber to ${topic}, connecting to ${uri}`, 733 | ); 734 | 735 | if (!this.isSubscribedTo(topic)) { 736 | return; 737 | } 738 | 739 | // Create a TCP socket connecting to this publisher 740 | const socket = await this._tcpSocketCreate({ host: address, port }); 741 | connection = new TcpConnection( 742 | socket, 743 | address, 744 | port, 745 | new Map([ 746 | ["topic", topic], 747 | ["md5sum", md5sum ?? "*"], 748 | ["callerid", this.name], 749 | ["type", dataType], 750 | ["tcp_nodelay", tcpNoDelay ? "1" : "0"], 751 | ]), 752 | this._log, 753 | ); 754 | 755 | if (!this.isSubscribedTo(topic)) { 756 | socket.close().catch((err) => { 757 | this._log?.warn?.( 758 | `closing connection to ${address}:${port} for topic "${topic}" failed: ${err}`, 759 | ); 760 | }); 761 | return; 762 | } 763 | 764 | // Hold a reference to this publisher 765 | const connectionId = this._newConnectionId(); 766 | subscription.addPublisher(connectionId, rosFollowerClient, connection); 767 | } catch (err) { 768 | // Consider tracking failed RosFollower connections (node XML-RPC servers) and entering a 769 | // retry loop 770 | this._log?.warn?.( 771 | `subscribing to ${topic} at ${pubUrl} failed (${err}), this connection will be dropped`, 772 | ); 773 | this.emit( 774 | "error", 775 | new Error( 776 | `Subscribing to ${topic} at ${pubUrl} failed (${err}), this connection will be dropped`, 777 | ), 778 | ); 779 | return; 780 | } 781 | 782 | // Asynchronously initiate the socket connection. This will enter a retry loop on failure 783 | connection.connect().catch((err) => { 784 | // This should never happen, connect() is assumed not to throw 785 | this._log?.warn?.( 786 | `connecting to ${address}:${port} for topic "${topic}" unexpectedly failed: ${err}`, 787 | ); 788 | }); 789 | } 790 | 791 | static GetRosHostname( 792 | getEnvVar: (envVar: string) => string | undefined, 793 | getHostname: () => string | undefined, 794 | getNetworkInterfaces: () => NetworkInterface[], 795 | ): string { 796 | // Prefer ROS_HOSTNAME, then ROS_IP env vars 797 | let hostname = getEnvVar("ROS_HOSTNAME") ?? getEnvVar("ROS_IP"); 798 | if (hostname != undefined && hostname.length > 0) { 799 | return hostname; 800 | } 801 | 802 | // Try to get the operating system hostname 803 | hostname = getHostname(); 804 | if (hostname != undefined && hostname.length > 0) { 805 | return hostname; 806 | } 807 | 808 | // Fall back to iterating network interfaces looking for an IP address 809 | let bestAddr: NetworkInterface | undefined; 810 | const ifaces = getNetworkInterfaces(); 811 | for (const iface of ifaces) { 812 | if ( 813 | (iface.family !== "IPv4" && iface.family !== "IPv6") || 814 | iface.internal || 815 | iface.address.length === 0 816 | ) { 817 | continue; 818 | } 819 | 820 | if (bestAddr == undefined) { 821 | // Use the first non-internal interface we find 822 | bestAddr = iface; 823 | } else if (RosNode.IsPrivateIP(bestAddr.address) && !RosNode.IsPrivateIP(iface.address)) { 824 | // Prefer public IPs over private 825 | bestAddr = iface; 826 | } else if (bestAddr.family !== "IPv6" && iface.family === "IPv6") { 827 | // Prefer IPv6 828 | bestAddr = iface; 829 | } 830 | } 831 | if (bestAddr != undefined) { 832 | return bestAddr.address; 833 | } 834 | 835 | // Last resort, return IPv4 loopback 836 | return "127.0.0.1"; 837 | } 838 | 839 | static IsPrivateIP(ip: string): boolean { 840 | // Logic based on isPrivateIP() in ros_comm network.cpp 841 | return ip.startsWith("192.168") || ip.startsWith("10.") || ip.startsWith("169.254"); 842 | } 843 | } 844 | --------------------------------------------------------------------------------