Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/core/Ros.ts
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ import {
import Topic from "./Topic.js";
import Service from "./Service.js";
import Param from "./Param.js";
import TFClient from "../tf/TFClient.js";
import TFClient from "../tf/TFClient";
import ActionClient from "../actionlib/ActionClient.js";
import SimpleActionServer from "../actionlib/SimpleActionServer.js";
import { EventEmitter } from "eventemitter3";
Expand Down
91 changes: 51 additions & 40 deletions src/tf/BaseTFClient.js → src/tf/BaseTFClient.ts
Original file line number Diff line number Diff line change
@@ -1,35 +1,41 @@
import Transform from "../math/Transform.js";
import { EventEmitter } from "eventemitter3";
import Ros from "../core/Ros.js";
import { tf2_msgs } from "../types/tf2_msgs.js";

/**
* Base class for TF Clients that provides common functionality.
*/
export default class BaseTFClient extends EventEmitter {
frameInfos = {};
frameInfos: Record<
string,
{ transform?: Transform; cbs: ((tf: Transform) => void)[] }
> = {};
republisherUpdateRequested = false;
/** @type {((tf: any) => any) | undefined} */
_subscribeCB = undefined;
_isDisposed = false;
ros;
fixedFrame;
angularThres;
transThres;
rate;
updateDelay;
topicTimeout;
serverName;
ros: Ros;
fixedFrame: string;
angularThres: number;
transThres: number;
rate: number;
updateDelay: number;
topicTimeout: {
sec: number;
nsec: number;
};
serverName: string;

/**
* @param {Object} options
* @param {import('../core/Ros.js').default} options.ros - The ROSLIB.Ros connection handle.
* @param {string} [options.fixedFrame=base_link] - The fixed frame.
* @param {number} [options.angularThres=2.0] - The angular threshold for the TF republisher.
* @param {number} [options.transThres=0.01] - The translation threshold for the TF republisher.
* @param {number} [options.rate=10.0] - The rate for the TF republisher.
* @param {number} [options.updateDelay=50] - The time (in ms) to wait after a new subscription
* @param options
* @param options.ros - The ROSLIB.Ros connection handle.
* @param [options.fixedFrame=base_link] - The fixed frame.
* @param [options.angularThres=2.0] - The angular threshold for the TF republisher.
* @param [options.transThres=0.01] - The translation threshold for the TF republisher.
* @param [options.rate=10.0] - The rate for the TF republisher.
* @param [options.updateDelay=50] - The time (in ms) to wait after a new subscription
* to update the TF republisher's list of TFs.
* @param {number} [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
* @param {string} [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
* @param [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
* @param [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
*/
constructor({
ros,
Expand All @@ -40,6 +46,15 @@ export default class BaseTFClient extends EventEmitter {
updateDelay = 50,
topicTimeout = 2.0,
serverName = "/tf2_web_republisher",
}: {
ros: Ros;
fixedFrame?: string;
angularThres?: number;
transThres?: number;
rate?: number;
updateDelay?: number;
topicTimeout?: number;
serverName?: string;
}) {
super();

Expand All @@ -53,8 +68,8 @@ export default class BaseTFClient extends EventEmitter {
const secs = Math.floor(seconds);
const nsecs = Math.floor((seconds - secs) * 1000000000);
this.topicTimeout = {
secs: secs,
nsecs: nsecs,
sec: secs,
nsec: nsecs,
};
this.serverName = serverName;
}
Expand All @@ -63,23 +78,22 @@ export default class BaseTFClient extends EventEmitter {
* Process the incoming TF message and send them out using the callback
* functions.
*
* @param {Object} tf - The TF message from the server.
* @param tf - The TF message from the server.
*/
processTFArray(tf) {
processTFArray(tf: tf2_msgs.TFMessage) {
tf.transforms.forEach((transform) => {
let frameID = transform.child_frame_id;
if (frameID[0] === "/") {
frameID = frameID.substring(1);
}
const info = this.frameInfos[frameID];
if (info) {
info.transform = new Transform({
const tf = new Transform({
translation: transform.transform.translation,
rotation: transform.transform.rotation,
});
info.cbs.forEach((cb) => {
cb(info.transform);
});
info.transform = tf;
info.cbs.forEach((cb) => cb(tf));
}
}, this);
}
Expand All @@ -93,17 +107,13 @@ export default class BaseTFClient extends EventEmitter {
throw new Error("updateGoal() must be implemented by subclass");
}

/**
* @callback subscribeCallback
* @param {Transform} callback.transform - The transform data.
*/
/**
* Subscribe to the given TF frame.
*
* @param {string} frameID - The TF frame to subscribe to.
* @param {subscribeCallback} callback - Function with the following params:
* @param frameID - The TF frame to subscribe to.
* @param callback - Function with the following params:
*/
subscribe(frameID, callback) {
subscribe(frameID: string, callback: (transform: Transform) => void) {
// remove leading slash, if it's there
if (frameID.startsWith("/")) {
frameID = frameID.substring(1);
Expand All @@ -120,19 +130,20 @@ export default class BaseTFClient extends EventEmitter {
}

// if we already have a transform, callback immediately
else if (this.frameInfos[frameID].transform) {
callback(this.frameInfos[frameID].transform);
const transform = this.frameInfos[frameID].transform;
if (transform) {
callback(transform);
}
this.frameInfos[frameID].cbs.push(callback);
}

/**
* Unsubscribe from the given TF frame.
*
* @param {string} frameID - The TF frame to unsubscribe from.
* @param {function} callback - The callback function to remove.
* @param frameID - The TF frame to unsubscribe from.
* @param callback - The callback function to remove.
*/
unsubscribe(frameID, callback) {
unsubscribe(frameID: string, callback: (transform: Transform) => void) {
// remove leading slash, if it's there
if (frameID.startsWith("/")) {
frameID = frameID.substring(1);
Expand Down
16 changes: 10 additions & 6 deletions src/tf/ROS2TFClient.js → src/tf/ROS2TFClient.ts
Original file line number Diff line number Diff line change
@@ -1,16 +1,20 @@
import { tf2_web_republisher } from "../types/tf2_web_republisher.js";
import Action from "../core/Action.js";
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;
actionClient;
currentGoal;
goal_id: string;
actionClient: Action<
tf2_web_republisher.TFSubscriptionGoal,
tf2_web_republisher.TFSubscriptionResult,
tf2_web_republisher.TFSubscriptionFeedback
>;
currentGoal: tf2_web_republisher.TFSubscriptionGoal;

/** @param {ConstructorParameters<typeof BaseTFClient>[0]} options */
constructor(options) {
constructor(options: ConstructorParameters<typeof BaseTFClient>[0]) {
super(options);

this.goal_id = "";
Expand Down Expand Up @@ -44,7 +48,7 @@ export default class ROS2TFClient extends BaseTFClient {
const id = this.actionClient.sendGoal(
goalMessage,
() => {},
(feedback) => {
(feedback: tf2_web_republisher.TFSubscriptionFeedback) => {
this.processTFArray(feedback);
},
);
Expand Down
67 changes: 42 additions & 25 deletions src/tf/TFClient.js → src/tf/TFClient.ts
Original file line number Diff line number Diff line change
Expand Up @@ -8,35 +8,53 @@ import Goal from "../actionlib/Goal.js";

import Service from "../core/Service.js";
import Topic from "../core/Topic.js";
import Ros from "../core/Ros.js";
import { tf2_msgs } from "../types/tf2_msgs.js";
import { tf2_web_republisher } from "../types/tf2_web_republisher.js";

import BaseTFClient from "./BaseTFClient.js";

/**
* A TF Client that listens to TFs from tf2_web_republisher.
*/
export default class TFClient extends BaseTFClient {
/** @type {Goal|false} */
currentGoal = false;
/** @type {Topic|false} */
currentTopic = false;
repubServiceName;
actionClient;
serviceClient;
currentGoal: Goal<tf2_web_republisher.TFSubscriptionGoal> | false = false;
currentTopic: Topic<tf2_msgs.TFMessage> | false = false;
repubServiceName: string;
actionClient: ActionClient<tf2_web_republisher.TFSubscriptionGoal>;
serviceClient: Service<
tf2_web_republisher.RepublishTFsRequest,
tf2_web_republisher.RepublishTFsResponse
>;
_subscribeCB: ((tf: tf2_msgs.TFMessage) => void) | undefined = undefined;

/**
* @param {Object} options
* @param {import('../core/Ros.js').default} options.ros - The ROSLIB.Ros connection handle.
* @param {string} [options.fixedFrame=base_link] - The fixed frame.
* @param {number} [options.angularThres=2.0] - The angular threshold for the TF republisher.
* @param {number} [options.transThres=0.01] - The translation threshold for the TF republisher.
* @param {number} [options.rate=10.0] - The rate for the TF republisher.
* @param {number} [options.updateDelay=50] - The time (in ms) to wait after a new subscription
* @param options
* @param options.ros - The ROSLIB.Ros connection handle.
* @param [options.fixedFrame=base_link] - The fixed frame.
* @param [options.angularThres=2.0] - The angular threshold for the TF republisher.
* @param [options.transThres=0.01] - The translation threshold for the TF republisher.
* @param [options.rate=10.0] - The rate for the TF republisher.
* @param [options.updateDelay=50] - The time (in ms) to wait after a new subscription
* to update the TF republisher's list of TFs.
* @param {number} [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
* @param {string} [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
* @param {string} [options.repubServiceName="/republish_tfs"] - The name of the republish_tfs service (non groovy compatibility mode only).
* @param [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
* @param [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
* @param [options.repubServiceName="/republish_tfs"] - The name of the republish_tfs service (non groovy compatibility mode only).
*/
constructor({ repubServiceName = "/republish_tfs", ...options }) {
constructor({
repubServiceName = "/republish_tfs",
...options
}: {
ros: Ros;
fixedFrame?: string;
angularThres?: number;
transThres?: number;
rate?: number;
updateDelay?: number;
topicTimeout?: number;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

preceded this PR, but topicTimeout should really be serviceTimeout ... however, not worth breaking anything for this i guess.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Preceded this PR by many years I think!!

serverName?: string;
repubServiceName?: string;
}) {
super(options);

this.repubServiceName = repubServiceName;
Expand All @@ -63,7 +81,7 @@ export default class TFClient extends BaseTFClient {
* based on the current list of TFs.
*/
updateGoal() {
const goalMessage = {
const goalMessage: tf2_web_republisher.TFSubscriptionGoal = {
source_frames: Object.keys(this.frameInfos),
target_frame: this.fixedFrame,
angular_thres: this.angularThres,
Expand All @@ -79,7 +97,7 @@ export default class TFClient extends BaseTFClient {
if (this.currentGoal) {
this.currentGoal.cancel();
}
this.currentGoal = new Goal({
this.currentGoal = new Goal<tf2_web_republisher.TFSubscriptionGoal>({
actionClient: this.actionClient,
goalMessage: goalMessage,
});
Expand All @@ -92,9 +110,8 @@ export default class TFClient extends BaseTFClient {
* The service interface has the same parameters as the action,
* plus the timeout
*/
goalMessage.timeout = this.topicTimeout;
this.serviceClient.callService(
goalMessage,
{ ...goalMessage, timeout: this.topicTimeout },
this.processResponse.bind(this),
);
}
Expand All @@ -106,9 +123,9 @@ export default class TFClient extends BaseTFClient {
* Process the service response and subscribe to the tf republisher
* topic.
*
* @param {Object} response - The service response containing the topic name.
* @param response - The service response containing the topic name.
*/
processResponse(response) {
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.
Expand All @@ -125,7 +142,7 @@ export default class TFClient extends BaseTFClient {
this.currentTopic.unsubscribe(this._subscribeCB);
}

this.currentTopic = new Topic({
this.currentTopic = new Topic<tf2_msgs.TFMessage>({
ros: this.ros,
name: response.topic_name,
messageType: "tf2_web_republisher/TFArray",
Expand Down
4 changes: 2 additions & 2 deletions src/tf/index.ts
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
export { default as TFClient } from "./TFClient.js";
export { default as ROS2TFClient } from "./ROS2TFClient.js";
export { default as TFClient } from "./TFClient";
export { default as ROS2TFClient } from "./ROS2TFClient";
22 changes: 22 additions & 0 deletions src/types/geometry_msgs.ts
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
export namespace geometry_msgs {
export interface TransformStamped {
// TODO: some sort of unholy union type of ros1 header and ros2 header???
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ros 1 is deprecated, so I'd just not bother and point people to use older versions of this library if they need ros 1

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed in theory, but at that point why not rip out the entire ROS 1 implementation of TFClient?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

and actionlib..

child_frame_id: string;
transform: Transform;
}
export interface Transform {
translation: Vector3;
rotation: Quaternion;
}
export interface Vector3 {
x: number;
y: number;
z: number;
}
export interface Quaternion {
x: number;
y: number;
z: number;
w: number;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

minor point, but in the ROS 2 message definition, the w field actually defaults to 1.0, whereas all the other scalar numeric fields default to 0.0. Is that something we can/should do here too?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

interfaces can't be instantiated, so you can't set defaults

}
}
7 changes: 7 additions & 0 deletions src/types/tf2_msgs.ts
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
import { geometry_msgs } from "./geometry_msgs";

export namespace tf2_msgs {
export interface TFMessage {
transforms: geometry_msgs.TransformStamped[];
}
}
28 changes: 28 additions & 0 deletions src/types/tf2_web_republisher.ts
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
import { geometry_msgs } from "./geometry_msgs";

export namespace tf2_web_republisher {
export interface RepublishTFsRequest extends TFSubscriptionGoal {
timeout: {
sec: number;
nsec: number;
};
}

export interface RepublishTFsResponse {
topic_name: string;
}

export interface TFSubscriptionGoal {
source_frames: string[];
target_frame: string;
angular_thres: number;
trans_thres: number;
rate: number;
}

export type TFSubscriptionResult = Record<never, never>;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what does it mean that this one is type vs the others being interface?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

type lets me use type expressions, like the assignment I'm doing here. interface only allows describing an object type as a block of fields in curly braces


export interface TFSubscriptionFeedback {
transforms: geometry_msgs.TransformStamped[];
}
}