diff --git a/README.md b/README.md index 5524e867e..5f7190732 100644 --- a/README.md +++ b/README.md @@ -18,10 +18,6 @@ Install roslibjs with any NPM-compatible package manager via, for example, npm install roslib ``` -~Pre-built files can be found in either [roslib.js](build/roslib.js) or [roslib.min.js](build/roslib.min.js).~ - -As we are updating to v2, we don't provide pre-built files anymore in the repo. - Alternatively, you can use the v1 release via the [JsDelivr](https://www.jsdelivr.com/) CDN: ([full](https://cdn.jsdelivr.net/npm/roslib@1/build/roslib.js)) | ([min](https://cdn.jsdelivr.net/npm/roslib@1/build/roslib.min.js)) ## Troubleshooting diff --git a/package.json b/package.json index f49e21667..51253632a 100644 --- a/package.json +++ b/package.json @@ -57,7 +57,7 @@ }, "scripts": { "build": "vite build", - "doc": "typedoc src/RosLib.ts", + "doc": "typedoc src/RosLib.ts --treatWarningsAsErrors", "lint": "eslint .", "test": "vitest", "prepublishOnly": "npm run test", diff --git a/src/RosLib.ts b/src/RosLib.ts index 8e30a84df..1ab164ee3 100644 --- a/src/RosLib.ts +++ b/src/RosLib.ts @@ -1,17 +1,17 @@ /** - * @fileOverview * @author Russell Toris - rctoris@wpi.edu */ -/** @description Library version */ +/** Library version */ export const REVISION = import.meta.env.VITE_ROSLIBJS_VERSION; // Core exports -export { default as Ros } from "./core/Ros.js"; +export { default as Ros, type TypeDefDict } from "./core/Ros.js"; export { default as Topic } from "./core/Topic.js"; export { default as Param } from "./core/Param.js"; export { default as Service } from "./core/Service.js"; export { default as Action } from "./core/Action.js"; +export { type GoalStatus } from "./core/GoalStatus.js"; // Core Transport exports export { @@ -45,6 +45,7 @@ export { default as UrdfCylinder } from "./urdf/UrdfCylinder.js"; export { default as UrdfLink } from "./urdf/UrdfLink.js"; export { default as UrdfMaterial } from "./urdf/UrdfMaterial.js"; export { default as UrdfMesh } from "./urdf/UrdfMesh.js"; +export { default as UrdfJoint } from "./urdf/UrdfJoint.js"; export { default as UrdfModel, type UrdfModelOptions, @@ -61,3 +62,11 @@ export { type UrdfDefaultOptions, } from "./urdf/UrdfTypes.js"; export { isElement, parseUrdfOrigin } from "./urdf/UrdfUtils.js"; + +// Only export the types Typedoc requires you to export - those are our API. Anything else is internal. +export type { rosapi } from "./types/rosapi"; +export type { actionlib_msgs } from "./types/actionlib_msgs"; +export type { std_msgs } from "./types/std_msgs"; +export type { tf2_msgs } from "./types/tf2_msgs"; +export type { geometry_msgs } from "./types/geometry_msgs"; +export type { RosbridgeMessage } from "./types/protocol.js"; diff --git a/src/actionlib/ActionClient.ts b/src/actionlib/ActionClient.ts index b3104d173..b95fe7145 100644 --- a/src/actionlib/ActionClient.ts +++ b/src/actionlib/ActionClient.ts @@ -36,17 +36,17 @@ export default class ActionClient< omitFeedback?: boolean; omitStatus?: boolean; omitResult?: boolean; - feedbackListener: Topic<{ + #feedbackListener: Topic<{ status: actionlib_msgs.GoalStatus; feedback: TFeedback; }>; - statusListener: Topic; - resultListener: Topic<{ + #statusListener: Topic; + #resultListener: Topic<{ status: actionlib_msgs.GoalStatus; result: TResult; }>; - goalTopic: Topic<{ goal: TGoal; goal_id: actionlib_msgs.GoalID }>; - cancelTopic: Topic>; + #goalTopic: Topic<{ goal: TGoal; goal_id: actionlib_msgs.GoalID }>; + #cancelTopic: Topic>; /** * @param options * @param options.ros - The ROSLIB.Ros connection handle. @@ -84,43 +84,43 @@ export default class ActionClient< this.omitResult = omitResult; // create the topics associated with actionlib - this.feedbackListener = new Topic({ + this.#feedbackListener = new Topic({ ros: this.ros, name: `${this.serverName}/feedback`, messageType: `${this.actionName}Feedback`, }); - this.statusListener = new Topic({ + this.#statusListener = new Topic({ ros: this.ros, name: `${this.serverName}/status`, messageType: "actionlib_msgs/GoalStatusArray", }); - this.resultListener = new Topic({ + this.#resultListener = new Topic({ ros: this.ros, name: `${this.serverName}/result`, messageType: `${this.actionName}Result`, }); - this.goalTopic = new Topic({ + this.#goalTopic = new Topic({ ros: this.ros, name: `${this.serverName}/goal`, messageType: `${this.actionName}Goal`, }); - this.cancelTopic = new Topic({ + this.#cancelTopic = new Topic({ ros: this.ros, name: `${this.serverName}/cancel`, messageType: "actionlib_msgs/GoalID", }); // advertise the goal and cancel topics - this.goalTopic.advertise(); - this.cancelTopic.advertise(); + this.#goalTopic.advertise(); + this.#cancelTopic.advertise(); // subscribe to the status topic if (!this.omitStatus) { - this.statusListener.subscribe((statusMessage) => { + this.#statusListener.subscribe((statusMessage) => { this.receivedStatus = true; statusMessage.status_list.forEach((status) => { const goal = this.goals[status.goal_id.id]; @@ -133,7 +133,7 @@ export default class ActionClient< // subscribe the the feedback topic if (!this.omitFeedback) { - this.feedbackListener.subscribe((feedbackMessage) => { + this.#feedbackListener.subscribe((feedbackMessage) => { const goal = this.goals[feedbackMessage.status.goal_id.id]; if (goal) { goal.emit("status", feedbackMessage.status); @@ -144,7 +144,7 @@ export default class ActionClient< // subscribe to the result topic if (!this.omitResult) { - this.resultListener.subscribe((resultMessage) => { + this.#resultListener.subscribe((resultMessage) => { const goal = this.goals[resultMessage.status.goal_id.id]; if (goal) { @@ -166,24 +166,31 @@ export default class ActionClient< /** * Cancel all goals associated with this ActionClient. */ - cancel() { - const cancelMessage = {}; - this.cancelTopic.publish(cancelMessage); + cancel(id?: string) { + const cancelMessage = { + id, + }; + this.#cancelTopic.publish(cancelMessage); } + + sendGoal(goal: { goal: TGoal; goal_id: actionlib_msgs.GoalID }) { + this.#goalTopic.publish(goal); + } + /** * Unsubscribe and unadvertise all topics associated with this ActionClient. */ dispose() { - this.goalTopic.unadvertise(); - this.cancelTopic.unadvertise(); + this.#goalTopic.unadvertise(); + this.#cancelTopic.unadvertise(); if (!this.omitStatus) { - this.statusListener.unsubscribe(); + this.#statusListener.unsubscribe(); } if (!this.omitFeedback) { - this.feedbackListener.unsubscribe(); + this.#feedbackListener.unsubscribe(); } if (!this.omitResult) { - this.resultListener.unsubscribe(); + this.#resultListener.unsubscribe(); } } } diff --git a/src/actionlib/Goal.ts b/src/actionlib/Goal.ts index d4c1f6f89..6de212a9e 100644 --- a/src/actionlib/Goal.ts +++ b/src/actionlib/Goal.ts @@ -81,7 +81,7 @@ export default class Goal< * @param [timeout] - A timeout length for the goal's result. */ send(timeout?: number) { - this.actionClient.goalTopic.publish(this.goalMessage); + this.actionClient.sendGoal(this.goalMessage); if (timeout) { setTimeout(() => { if (!this.isFinished) { @@ -94,9 +94,6 @@ export default class Goal< * Cancel the current goal. */ cancel() { - const cancelMessage = { - id: this.goalID, - }; - this.actionClient.cancelTopic.publish(cancelMessage); + this.actionClient.cancel(this.goalID); } } diff --git a/src/actionlib/SimpleActionServer.ts b/src/actionlib/SimpleActionServer.ts index f6183a5d1..9bec13a07 100644 --- a/src/actionlib/SimpleActionServer.ts +++ b/src/actionlib/SimpleActionServer.ts @@ -25,21 +25,21 @@ export default class SimpleActionServer< cancel: undefined; }> { // needed for handling preemption prompted by a new goal being received - currentGoal: { goal: TGoal; goal_id: actionlib_msgs.GoalID } | null = null; // currently tracked goal - nextGoal: { goal: TGoal; goal_id: actionlib_msgs.GoalID } | null = null; // the one this'll be preempting + #currentGoal: { goal: TGoal; goal_id: actionlib_msgs.GoalID } | null = null; // currently tracked goal + #nextGoal: { goal: TGoal; goal_id: actionlib_msgs.GoalID } | null = null; // the one this'll be preempting ros: Ros; serverName: string; actionName: string; - feedbackPublisher: Topic<{ + #feedbackPublisher: Topic<{ feedback: TFeedback; status: actionlib_msgs.GoalStatus; }>; - resultPublisher: Topic<{ + #resultPublisher: Topic<{ result?: TResult; status: actionlib_msgs.GoalStatus; }>; - statusPublisher?: Topic; - statusMessage: actionlib_msgs.GoalStatusArray; + #statusPublisher?: Topic; + #statusMessage: actionlib_msgs.GoalStatusArray; /** * @param options * @param options.ros - The ROSLIB.Ros connection handle. @@ -61,12 +61,12 @@ export default class SimpleActionServer< this.actionName = actionName; // create and advertise publishers - this.feedbackPublisher = new Topic({ + this.#feedbackPublisher = new Topic({ ros: this.ros, name: `${this.serverName}/feedback`, messageType: `${this.actionName}Feedback`, }); - this.feedbackPublisher.advertise(); + this.#feedbackPublisher.advertise(); const statusPublisher = new Topic({ ros: this.ros, @@ -75,12 +75,12 @@ export default class SimpleActionServer< }); statusPublisher.advertise(); - this.resultPublisher = new Topic({ + this.#resultPublisher = new Topic({ ros: this.ros, name: `${this.serverName}/result`, messageType: `${this.actionName}Result`, }); - this.resultPublisher.advertise(); + this.#resultPublisher.advertise(); // create and subscribe to listeners const goalListener = new Topic<{ @@ -99,7 +99,7 @@ export default class SimpleActionServer< }); // Track the goals and their status in order to publish status... - this.statusMessage = { + this.#statusMessage = { header: { stamp: { secs: 0, nsecs: 100 }, frame_id: "", @@ -109,15 +109,15 @@ export default class SimpleActionServer< }; goalListener.subscribe((goalMessage) => { - if (this.currentGoal) { - this.nextGoal = goalMessage; + if (this.#currentGoal) { + this.#nextGoal = goalMessage; // needs to happen AFTER rest is set up this.emit("cancel"); } else { - this.statusMessage.status_list = [ + this.#statusMessage.status_list = [ { goal_id: goalMessage.goal_id, status: 1 }, ]; - this.currentGoal = goalMessage; + this.#currentGoal = goalMessage; this.emit("goal", goalMessage.goal); } }); @@ -151,33 +151,33 @@ export default class SimpleActionServer< cancelMessage.stamp.nsecs === 0 && cancelMessage.id === "" ) { - this.nextGoal = null; - if (this.currentGoal) { + this.#nextGoal = null; + if (this.#currentGoal) { this.emit("cancel"); } } else { // treat id and stamp independently if ( - this.currentGoal && - cancelMessage.id === this.currentGoal.goal_id.id + this.#currentGoal && + cancelMessage.id === this.#currentGoal.goal_id.id ) { this.emit("cancel"); } else if ( - this.nextGoal && - cancelMessage.id === this.nextGoal.goal_id.id + this.#nextGoal && + cancelMessage.id === this.#nextGoal.goal_id.id ) { - this.nextGoal = null; + this.#nextGoal = null; } if ( - this.nextGoal && - isEarlier(this.nextGoal.goal_id.stamp, cancelMessage.stamp) + this.#nextGoal && + isEarlier(this.#nextGoal.goal_id.stamp, cancelMessage.stamp) ) { - this.nextGoal = null; + this.#nextGoal = null; } if ( - this.currentGoal && - isEarlier(this.currentGoal.goal_id.stamp, cancelMessage.stamp) + this.#currentGoal && + isEarlier(this.#currentGoal.goal_id.stamp, cancelMessage.stamp) ) { this.emit("cancel"); } @@ -191,11 +191,11 @@ export default class SimpleActionServer< const nsecs = Math.round( 1000000000 * (currentTime.getTime() / 1000 - secs), ); - this.statusMessage.header = { - ...this.statusMessage.header, + this.#statusMessage.header = { + ...this.#statusMessage.header, stamp: { secs, nsecs }, }; - statusPublisher.publish(this.statusMessage); + this.#statusPublisher?.publish(this.#statusMessage); }, 500); // publish every 500ms } /** @@ -204,20 +204,20 @@ export default class SimpleActionServer< * @param result - The result to return to the client. */ setSucceeded(result: TResult) { - if (this.currentGoal !== null) { + if (this.#currentGoal !== null) { const resultMessage = { - status: { goal_id: this.currentGoal.goal_id, status: 3 }, + status: { goal_id: this.#currentGoal.goal_id, status: 3 }, result: result, }; - this.resultPublisher.publish(resultMessage); + this.#resultPublisher.publish(resultMessage); - this.statusMessage.status_list = []; - if (this.nextGoal) { - this.currentGoal = this.nextGoal; - this.nextGoal = null; - this.emit("goal", this.currentGoal.goal); + this.#statusMessage.status_list = []; + if (this.#nextGoal) { + this.#currentGoal = this.#nextGoal; + this.#nextGoal = null; + this.emit("goal", this.#currentGoal.goal); } else { - this.currentGoal = null; + this.#currentGoal = null; } } } @@ -227,20 +227,20 @@ export default class SimpleActionServer< * @param result - The result to return to the client. */ setAborted(result: TResult) { - if (this.currentGoal !== null) { + if (this.#currentGoal !== null) { const resultMessage = { - status: { goal_id: this.currentGoal.goal_id, status: 4 }, + status: { goal_id: this.#currentGoal.goal_id, status: 4 }, result: result, }; - this.resultPublisher.publish(resultMessage); + this.#resultPublisher.publish(resultMessage); - this.statusMessage.status_list = []; - if (this.nextGoal) { - this.currentGoal = this.nextGoal; - this.nextGoal = null; - this.emit("goal", this.currentGoal.goal); + this.#statusMessage.status_list = []; + if (this.#nextGoal) { + this.#currentGoal = this.#nextGoal; + this.#nextGoal = null; + this.emit("goal", this.#currentGoal.goal); } else { - this.currentGoal = null; + this.#currentGoal = null; } } } @@ -250,31 +250,31 @@ export default class SimpleActionServer< * @param feedback - The feedback to send to the client. */ sendFeedback(feedback: TFeedback) { - if (this.currentGoal !== null) { + if (this.#currentGoal !== null) { const feedbackMessage = { - status: { goal_id: this.currentGoal.goal_id, status: 1 }, + status: { goal_id: this.#currentGoal.goal_id, status: 1 }, feedback: feedback, }; - this.feedbackPublisher.publish(feedbackMessage); + this.#feedbackPublisher.publish(feedbackMessage); } } /** * Handle case where client requests preemption. */ setPreempted() { - if (this.currentGoal !== null) { - this.statusMessage.status_list = []; + if (this.#currentGoal !== null) { + this.#statusMessage.status_list = []; const resultMessage = { - status: { goal_id: this.currentGoal.goal_id, status: 2 }, + status: { goal_id: this.#currentGoal.goal_id, status: 2 }, }; - this.resultPublisher.publish(resultMessage); + this.#resultPublisher.publish(resultMessage); - if (this.nextGoal) { - this.currentGoal = this.nextGoal; - this.nextGoal = null; - this.emit("goal", this.currentGoal.goal); + if (this.#nextGoal) { + this.#currentGoal = this.#nextGoal; + this.#nextGoal = null; + this.emit("goal", this.#currentGoal.goal); } else { - this.currentGoal = null; + this.#currentGoal = null; } } } diff --git a/src/core/Ros.ts b/src/core/Ros.ts index 0b75188e1..636452c73 100644 --- a/src/core/Ros.ts +++ b/src/core/Ros.ts @@ -33,7 +33,7 @@ import type { } from "./transport/Transport.js"; import { WebSocketTransportFactory } from "./transport/WebSocketTransportFactory.ts"; -interface TypeDefDict { +export interface TypeDefDict { [key: string]: string | string[] | TypeDefDict | TypeDefDict[]; } diff --git a/src/core/Topic.ts b/src/core/Topic.ts index ab291c874..a0540e03f 100644 --- a/src/core/Topic.ts +++ b/src/core/Topic.ts @@ -40,7 +40,7 @@ export default class Topic extends EventEmitter<{ queue_size: number; queue_length: number; reconnect_on_close: boolean; - callForSubscribeAndAdvertise: ( + #callForSubscribeAndAdvertise: ( message: RosbridgeSubscribeMessage | RosbridgeAdvertiseMessage, ) => void; subscribeId: string | null = null; @@ -117,7 +117,7 @@ export default class Topic extends EventEmitter<{ } if (this.reconnect_on_close) { - this.callForSubscribeAndAdvertise = (message) => { + this.#callForSubscribeAndAdvertise = (message) => { this.ros.callOnConnection(message); this.waitForReconnect = false; @@ -133,7 +133,7 @@ export default class Topic extends EventEmitter<{ this.ros.on("close", this.reconnectFunc); }; } else { - this.callForSubscribeAndAdvertise = (msg) => { + this.#callForSubscribeAndAdvertise = (msg) => { this.ros.callOnConnection(msg); }; } @@ -163,7 +163,7 @@ export default class Topic extends EventEmitter<{ this.ros.on(this.name, this.#messageCallback); this.subscribeId = `subscribe:${this.name}:${uuidv4()}`; - this.callForSubscribeAndAdvertise({ + this.#callForSubscribeAndAdvertise({ op: "subscribe", id: this.subscribeId, type: this.messageType, @@ -214,7 +214,7 @@ export default class Topic extends EventEmitter<{ return; } this.advertiseId = `advertise:${this.name}:${uuidv4()}`; - this.callForSubscribeAndAdvertise({ + this.#callForSubscribeAndAdvertise({ op: "advertise", id: this.advertiseId, type: this.messageType, diff --git a/src/math/Pose.ts b/src/math/Pose.ts index 0322888ae..7682756f7 100644 --- a/src/math/Pose.ts +++ b/src/math/Pose.ts @@ -5,7 +5,6 @@ import Vector3, { type IVector3 } from "./Vector3.js"; import Quaternion, { type IQuaternion } from "./Quaternion.js"; import { type ITransform } from "./Transform.js"; -import type { PartialNullable } from "../types/interface-types.js"; export interface IPose { /** @@ -25,7 +24,7 @@ export default class Pose implements IPose { position: Vector3; orientation: Quaternion; - constructor(options?: PartialNullable) { + constructor(options?: Partial) { this.position = new Vector3(options?.position); this.orientation = new Quaternion(options?.orientation); } diff --git a/src/math/Quaternion.ts b/src/math/Quaternion.ts index eed85fb9e..773453951 100644 --- a/src/math/Quaternion.ts +++ b/src/math/Quaternion.ts @@ -1,8 +1,6 @@ /** - * @fileOverview * @author David Gossow - dgossow@willowgarage.com */ -import { type PartialNullable } from "../types/interface-types.js"; export interface IQuaternion { /** @@ -35,7 +33,7 @@ export default class Quaternion implements IQuaternion { z: number; w: number; - constructor(options?: PartialNullable | null) { + constructor(options?: Partial | null) { this.x = options?.x ?? 0; this.y = options?.y ?? 0; this.z = options?.z ?? 0; diff --git a/src/math/Vector3.ts b/src/math/Vector3.ts index 9420a46fa..599d77f63 100644 --- a/src/math/Vector3.ts +++ b/src/math/Vector3.ts @@ -4,7 +4,6 @@ */ import { type IQuaternion } from "./Quaternion.js"; -import { type PartialNullable } from "../types/interface-types.js"; export interface IVector3 { /** @@ -29,7 +28,7 @@ export default class Vector3 implements IVector3 { y: number; z: number; - constructor(options?: PartialNullable | null) { + constructor(options?: Partial | null) { this.x = options?.x ?? 0; this.y = options?.y ?? 0; this.z = options?.z ?? 0; diff --git a/src/tf/ROS2TFClient.ts b/src/tf/ROS2TFClient.ts index 7ab405a51..0c6b08dd2 100644 --- a/src/tf/ROS2TFClient.ts +++ b/src/tf/ROS2TFClient.ts @@ -6,21 +6,20 @@ import BaseTFClient from "./BaseTFClient.js"; * A TF Client that listens to TFs from tf2_web_republisher using ROS2 actions. */ export default class ROS2TFClient extends BaseTFClient { - goal_id: string; - actionClient: Action< + #goalId: string; + #actionClient: Action< tf2_web_republisher.TFSubscriptionGoal, tf2_web_republisher.TFSubscriptionFeedback, tf2_web_republisher.TFSubscriptionResult >; - currentGoal?: tf2_web_republisher.TFSubscriptionGoal; constructor(options: ConstructorParameters[0]) { super(options); - this.goal_id = ""; + this.#goalId = ""; // Create an Action Client for ROS2 - this.actionClient = new Action({ + this.#actionClient = new Action({ ros: this.ros, name: this.serverName, actionType: "tf2_web_republisher_interfaces/TFSubscription", @@ -40,12 +39,11 @@ export default class ROS2TFClient extends BaseTFClient { rate: this.rate, }; - if (this.goal_id !== "") { - this.actionClient.cancelGoal(this.goal_id); + if (this.#goalId !== "") { + this.#actionClient.cancelGoal(this.#goalId); } - this.currentGoal = goalMessage; - const id = this.actionClient.sendGoal( + const id = this.#actionClient.sendGoal( goalMessage, () => {}, (feedback: tf2_web_republisher.TFSubscriptionFeedback) => { @@ -53,7 +51,7 @@ export default class ROS2TFClient extends BaseTFClient { }, ); if (typeof id === "string") { - this.goal_id = id; + this.#goalId = id; } this.republisherUpdateRequested = false; @@ -63,8 +61,8 @@ export default class ROS2TFClient extends BaseTFClient { * Unsubscribe and unadvertise all topics associated with this TFClient. */ dispose() { - if (this.goal_id !== "") { - this.actionClient.cancelGoal(this.goal_id); + if (this.#goalId !== "") { + this.#actionClient.cancelGoal(this.#goalId); } } } diff --git a/src/tf/TFClient.ts b/src/tf/TFClient.ts index 8ce6c06c1..5ebb75ee4 100644 --- a/src/tf/TFClient.ts +++ b/src/tf/TFClient.ts @@ -6,8 +6,6 @@ import ActionClient from "../actionlib/ActionClient.js"; import Goal from "../actionlib/Goal.js"; -import Topic from "../core/Topic.js"; -import type { tf2_msgs } from "../types/tf2_msgs.js"; import type { tf2_web_republisher } from "../types/tf2_web_republisher.js"; import BaseTFClient from "./BaseTFClient.js"; @@ -16,19 +14,16 @@ import BaseTFClient from "./BaseTFClient.js"; * A TF Client that listens to TFs from tf2_web_republisher. */ export default class TFClient extends BaseTFClient { - currentGoal: + #currentGoal: | Goal< tf2_web_republisher.TFSubscriptionGoal, tf2_web_republisher.TFSubscriptionFeedback > | false = false; - currentTopic: Topic | false = false; - actionClient: ActionClient< + #actionClient: ActionClient< tf2_web_republisher.TFSubscriptionGoal, tf2_web_republisher.TFSubscriptionFeedback >; - #subscribeCB: ((tf: tf2_msgs.TFMessage) => void) | undefined = undefined; - #isDisposed = false; /** * @param options @@ -46,7 +41,7 @@ export default class TFClient extends BaseTFClient { super(options); // Create an Action Client - this.actionClient = new ActionClient({ + this.#actionClient = new ActionClient({ ros: this.ros, serverName: this.serverName, actionName: "tf2_web_republisher/TFSubscriptionAction", @@ -68,64 +63,26 @@ export default class TFClient extends BaseTFClient { rate: this.rate, }; - if (this.currentGoal) { - this.currentGoal.cancel(); + if (this.#currentGoal) { + this.#currentGoal.cancel(); } - this.currentGoal = new Goal({ - actionClient: this.actionClient, + this.#currentGoal = new Goal({ + actionClient: this.#actionClient, goalMessage: goalMessage, }); - this.currentGoal.on("feedback", (feedback) => { + this.#currentGoal.on("feedback", (feedback) => { this.processTFArray(feedback); }); - this.currentGoal.send(); + this.#currentGoal.send(); this.republisherUpdateRequested = false; } - /** - * Process the service response and subscribe to the tf republisher - * topic. - * - * @param response - The service response containing the topic name. - */ - processResponse(response: tf2_web_republisher.RepublishTFsResponse) { - /* - * Do not setup a topic subscription if already disposed. Prevents a race condition where - * The dispose() function is called before the service call receives a response. - */ - if (this.#isDisposed) { - return; - } - - /* - * if we subscribed to a topic before, unsubscribe so - * the republisher stops publishing it - */ - if (this.currentTopic) { - this.currentTopic.unsubscribe(this.#subscribeCB); - } - - this.currentTopic = new Topic({ - ros: this.ros, - name: response.topic_name, - messageType: "tf2_web_republisher/TFArray", - }); - this.#subscribeCB = (response) => { - this.processTFArray(response); - }; - this.currentTopic.subscribe(this.#subscribeCB); - } - /** * Unsubscribe and unadvertise all topics associated with this TFClient. */ dispose() { - this.#isDisposed = true; - this.actionClient.dispose(); - if (this.currentTopic) { - this.currentTopic.unsubscribe(this.#subscribeCB); - } + this.#actionClient.dispose(); } } diff --git a/src/types/interface-types.ts b/src/types/interface-types.ts deleted file mode 100644 index 1fbe2a89c..000000000 --- a/src/types/interface-types.ts +++ /dev/null @@ -1,16 +0,0 @@ -/** - * Represents a type that can either be a value of type `T` or `undefined`. - */ -export type Optional = T | undefined; - -/** - * Represents a type that can either be a value of type `T` or `null`. - */ -export type Nullable = T | null; - -/** - * Represents an object type where all properties are optional, and included properties can be null or undefined. - */ -export type PartialNullable = { - [P in keyof T]?: Nullable; -}; diff --git a/src/types/rosapi.ts b/src/types/rosapi.ts index 652b3215f..a46ab4f90 100644 --- a/src/types/rosapi.ts +++ b/src/types/rosapi.ts @@ -30,15 +30,15 @@ export namespace rosapi { name: string; default?: string; } - interface GetParamResponsePreJazzy { + export interface GetParamResponsePreJazzy { value: string; } - interface GetParamResponseFailedPostJazzy { + export interface GetParamResponseFailedPostJazzy { value: never; successful: false; reason: string; } - interface GetParamResponseSuccessPostJazzy { + export interface GetParamResponseSuccessPostJazzy { value: string; successful: true; reason: never; @@ -51,12 +51,12 @@ export namespace rosapi { name: string; value: string; } - type SetParamResponsePreJazzy = Record; - interface FailedSetParamResponsePostJazzy { + export type SetParamResponsePreJazzy = Record; + export interface FailedSetParamResponsePostJazzy { successful: false; reason: string; } - interface SuccessfulSetParamResponsePostJazzy { + export interface SuccessfulSetParamResponsePostJazzy { successful: true; reason: never; } @@ -67,12 +67,12 @@ export namespace rosapi { export interface DeleteParamRequest { name: string; } - type DeleteParamResponsePreJazzy = Record; - interface FailedDeleteParamResponsePostJazzy { + export type DeleteParamResponsePreJazzy = Record; + export interface FailedDeleteParamResponsePostJazzy { successful: false; reason: string; } - interface SuccessfulDeleteParamResponsePostJazzy { + export interface SuccessfulDeleteParamResponsePostJazzy { successful: true; reason: never; } diff --git a/src/urdf/UrdfBox.ts b/src/urdf/UrdfBox.ts index 184a8cb33..e7bc2ff2a 100644 --- a/src/urdf/UrdfBox.ts +++ b/src/urdf/UrdfBox.ts @@ -6,22 +6,19 @@ import Vector3 from "../math/Vector3.js"; import { UrdfAttrs, UrdfType, type UrdfDefaultOptions } from "./UrdfTypes.js"; -import type { Optional, Nullable } from "../types/interface-types.js"; /** * A Box element in a URDF. */ export default class UrdfBox { type: UrdfType; - dimension: Nullable = null; + dimension: Vector3 | null = null; constructor({ xml }: UrdfDefaultOptions) { this.type = UrdfType.BOX; // Parse the xml string - const size: Optional = xml - .getAttribute(UrdfAttrs.Size) - ?.split(" "); + const size = xml.getAttribute(UrdfAttrs.Size)?.split(" "); if (!(size?.[0] && size[1] && size[2])) { return; } diff --git a/src/urdf/UrdfColor.ts b/src/urdf/UrdfColor.ts index cc1127aa5..4f03b9cee 100644 --- a/src/urdf/UrdfColor.ts +++ b/src/urdf/UrdfColor.ts @@ -5,7 +5,6 @@ */ import { UrdfAttrs, type UrdfDefaultOptions } from "./UrdfTypes.js"; -import type { Optional } from "../types/interface-types.js"; /** * A Color element in a URDF. @@ -30,9 +29,7 @@ export default class UrdfColor { constructor({ xml }: UrdfDefaultOptions) { // Parse the xml string - const rgba: Optional = xml - .getAttribute(UrdfAttrs.Rgba) - ?.split(" "); + const rgba = xml.getAttribute(UrdfAttrs.Rgba)?.split(" "); if (!(rgba?.[0] && rgba[1] && rgba[2] && rgba[3])) { return; } diff --git a/src/urdf/UrdfJoint.ts b/src/urdf/UrdfJoint.ts index 7e0026ff7..559e135d0 100644 --- a/src/urdf/UrdfJoint.ts +++ b/src/urdf/UrdfJoint.ts @@ -7,16 +7,15 @@ import { UrdfAttrs, type UrdfDefaultOptions } from "./UrdfTypes.js"; import Pose from "../math/Pose.js"; import Vector3 from "../math/Vector3.js"; import { parseUrdfOrigin } from "./UrdfUtils.js"; -import type { Nullable } from "../types/interface-types.js"; /** * A Joint element in a URDF. */ export default class UrdfJoint { name: string; - type: Nullable; - parent: Nullable = null; - child: Nullable = null; + type: string | null; + parent: string | null = null; + child: string | null = null; minval = NaN; maxval = NaN; origin: Pose = new Pose(); diff --git a/src/urdf/UrdfMaterial.ts b/src/urdf/UrdfMaterial.ts index 385f360aa..4ae10138d 100644 --- a/src/urdf/UrdfMaterial.ts +++ b/src/urdf/UrdfMaterial.ts @@ -6,15 +6,14 @@ import UrdfColor from "./UrdfColor.js"; import { UrdfAttrs, type UrdfDefaultOptions } from "./UrdfTypes.js"; -import type { Nullable } from "../types/interface-types.js"; /** * A Material element in a URDF. */ export default class UrdfMaterial { name: string; - textureFilename: Nullable = null; - color: Nullable = null; + textureFilename: string | null = null; + color: UrdfColor | null = null; constructor({ xml }: UrdfDefaultOptions) { this.name = xml.getAttribute(UrdfAttrs.Name) ?? "unknown_name"; diff --git a/src/urdf/UrdfMesh.ts b/src/urdf/UrdfMesh.ts index c876d1bcc..8e914252a 100644 --- a/src/urdf/UrdfMesh.ts +++ b/src/urdf/UrdfMesh.ts @@ -6,24 +6,21 @@ import Vector3 from "../math/Vector3.js"; import { UrdfAttrs, type UrdfDefaultOptions, UrdfType } from "./UrdfTypes.js"; -import type { Nullable, Optional } from "../types/interface-types.js"; /** * A Mesh element in a URDF. */ export default class UrdfMesh { type: UrdfType; - scale: Nullable = null; - filename: Nullable; + scale: Vector3 | null = null; + filename: string | null; constructor({ xml }: UrdfDefaultOptions) { this.type = UrdfType.MESH; this.filename = xml.getAttribute(UrdfAttrs.Filename); // Check for a scale - const scale: Optional = xml - .getAttribute(UrdfAttrs.Scale) - ?.split(" "); + const scale = xml.getAttribute(UrdfAttrs.Scale)?.split(" "); if (!(scale?.[0] && scale[1] && scale[2])) { return; } diff --git a/test/quaternion.test.ts b/test/quaternion.test.ts index d1ace7f10..fb72d1429 100644 --- a/test/quaternion.test.ts +++ b/test/quaternion.test.ts @@ -17,8 +17,13 @@ describe("Quaternion", function () { expect(q.z).to.equal(0); expect(q.w).to.equal(1); }); - it("should return an identity quaternion when null is specified", function () { - const q = new ROSLIB.Quaternion({ x: null, y: null, z: null, w: null }); + it("should return an identity quaternion when params are undefined", function () { + const q = new ROSLIB.Quaternion({ + x: undefined, + y: undefined, + z: undefined, + w: undefined, + }); expect(q.x).to.equal(0); expect(q.y).to.equal(0); expect(q.z).to.equal(0); diff --git a/test/tfclient.test.ts b/test/tfclient.test.ts deleted file mode 100644 index 19b53c209..000000000 --- a/test/tfclient.test.ts +++ /dev/null @@ -1,29 +0,0 @@ -import { describe, it, expect } from "vitest"; -import * as ROSLIB from "../src/RosLib.js"; - -describe("TFClient", function () { - describe("dispose", function () { - it("should not subscribe to republished topic if already disposed", function () { - /* - * This test makes sure we do not subscribe to the republished topic if the - * tf client has already been disposed when we get the response (from the setup request) - * from the server. - */ - - const dummyROS = { - on: () => {}, - off: () => {}, - callOnConnection: () => {}, - }; - - // @ts-expect-error -- stub impl - const tfclient = new ROSLIB.TFClient({ ros: dummyROS }); - tfclient.dispose(); - - // Simulated a response from the server after the client is already disposed - tfclient.processResponse({ topic_name: "/repub_1" }); - - expect(tfclient.currentTopic).toBeFalsy(); - }); - }); -});