Skip to content

Commit a1c6f38

Browse files
authored
Port TFClient impls to TypeScript (#1009)
1 parent 205e623 commit a1c6f38

File tree

8 files changed

+163
-74
lines changed

8 files changed

+163
-74
lines changed

src/core/Ros.ts

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ import {
1919
import Topic from "./Topic.js";
2020
import Service from "./Service.js";
2121
import Param from "./Param.js";
22-
import TFClient from "../tf/TFClient.js";
22+
import TFClient from "../tf/TFClient";
2323
import ActionClient from "../actionlib/ActionClient.js";
2424
import SimpleActionServer from "../actionlib/SimpleActionServer.js";
2525
import { EventEmitter } from "eventemitter3";

src/tf/BaseTFClient.js renamed to src/tf/BaseTFClient.ts

Lines changed: 51 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,35 +1,41 @@
11
import Transform from "../math/Transform.js";
22
import { EventEmitter } from "eventemitter3";
3+
import Ros from "../core/Ros.js";
4+
import { tf2_msgs } from "../types/tf2_msgs.js";
35

46
/**
57
* Base class for TF Clients that provides common functionality.
68
*/
79
export default class BaseTFClient extends EventEmitter {
8-
frameInfos = {};
10+
frameInfos: Record<
11+
string,
12+
{ transform?: Transform; cbs: ((tf: Transform) => void)[] }
13+
> = {};
914
republisherUpdateRequested = false;
10-
/** @type {((tf: any) => any) | undefined} */
11-
_subscribeCB = undefined;
1215
_isDisposed = false;
13-
ros;
14-
fixedFrame;
15-
angularThres;
16-
transThres;
17-
rate;
18-
updateDelay;
19-
topicTimeout;
20-
serverName;
16+
ros: Ros;
17+
fixedFrame: string;
18+
angularThres: number;
19+
transThres: number;
20+
rate: number;
21+
updateDelay: number;
22+
topicTimeout: {
23+
sec: number;
24+
nsec: number;
25+
};
26+
serverName: string;
2127

2228
/**
23-
* @param {Object} options
24-
* @param {import('../core/Ros.js').default} options.ros - The ROSLIB.Ros connection handle.
25-
* @param {string} [options.fixedFrame=base_link] - The fixed frame.
26-
* @param {number} [options.angularThres=2.0] - The angular threshold for the TF republisher.
27-
* @param {number} [options.transThres=0.01] - The translation threshold for the TF republisher.
28-
* @param {number} [options.rate=10.0] - The rate for the TF republisher.
29-
* @param {number} [options.updateDelay=50] - The time (in ms) to wait after a new subscription
29+
* @param options
30+
* @param options.ros - The ROSLIB.Ros connection handle.
31+
* @param [options.fixedFrame=base_link] - The fixed frame.
32+
* @param [options.angularThres=2.0] - The angular threshold for the TF republisher.
33+
* @param [options.transThres=0.01] - The translation threshold for the TF republisher.
34+
* @param [options.rate=10.0] - The rate for the TF republisher.
35+
* @param [options.updateDelay=50] - The time (in ms) to wait after a new subscription
3036
* to update the TF republisher's list of TFs.
31-
* @param {number} [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
32-
* @param {string} [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
37+
* @param [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
38+
* @param [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
3339
*/
3440
constructor({
3541
ros,
@@ -40,6 +46,15 @@ export default class BaseTFClient extends EventEmitter {
4046
updateDelay = 50,
4147
topicTimeout = 2.0,
4248
serverName = "/tf2_web_republisher",
49+
}: {
50+
ros: Ros;
51+
fixedFrame?: string;
52+
angularThres?: number;
53+
transThres?: number;
54+
rate?: number;
55+
updateDelay?: number;
56+
topicTimeout?: number;
57+
serverName?: string;
4358
}) {
4459
super();
4560

@@ -53,8 +68,8 @@ export default class BaseTFClient extends EventEmitter {
5368
const secs = Math.floor(seconds);
5469
const nsecs = Math.floor((seconds - secs) * 1000000000);
5570
this.topicTimeout = {
56-
secs: secs,
57-
nsecs: nsecs,
71+
sec: secs,
72+
nsec: nsecs,
5873
};
5974
this.serverName = serverName;
6075
}
@@ -63,23 +78,22 @@ export default class BaseTFClient extends EventEmitter {
6378
* Process the incoming TF message and send them out using the callback
6479
* functions.
6580
*
66-
* @param {Object} tf - The TF message from the server.
81+
* @param tf - The TF message from the server.
6782
*/
68-
processTFArray(tf) {
83+
processTFArray(tf: tf2_msgs.TFMessage) {
6984
tf.transforms.forEach((transform) => {
7085
let frameID = transform.child_frame_id;
7186
if (frameID[0] === "/") {
7287
frameID = frameID.substring(1);
7388
}
7489
const info = this.frameInfos[frameID];
7590
if (info) {
76-
info.transform = new Transform({
91+
const tf = new Transform({
7792
translation: transform.transform.translation,
7893
rotation: transform.transform.rotation,
7994
});
80-
info.cbs.forEach((cb) => {
81-
cb(info.transform);
82-
});
95+
info.transform = tf;
96+
info.cbs.forEach((cb) => cb(tf));
8397
}
8498
}, this);
8599
}
@@ -93,17 +107,13 @@ export default class BaseTFClient extends EventEmitter {
93107
throw new Error("updateGoal() must be implemented by subclass");
94108
}
95109

96-
/**
97-
* @callback subscribeCallback
98-
* @param {Transform} callback.transform - The transform data.
99-
*/
100110
/**
101111
* Subscribe to the given TF frame.
102112
*
103-
* @param {string} frameID - The TF frame to subscribe to.
104-
* @param {subscribeCallback} callback - Function with the following params:
113+
* @param frameID - The TF frame to subscribe to.
114+
* @param callback - Function with the following params:
105115
*/
106-
subscribe(frameID, callback) {
116+
subscribe(frameID: string, callback: (transform: Transform) => void) {
107117
// remove leading slash, if it's there
108118
if (frameID.startsWith("/")) {
109119
frameID = frameID.substring(1);
@@ -120,19 +130,20 @@ export default class BaseTFClient extends EventEmitter {
120130
}
121131

122132
// if we already have a transform, callback immediately
123-
else if (this.frameInfos[frameID].transform) {
124-
callback(this.frameInfos[frameID].transform);
133+
const transform = this.frameInfos[frameID].transform;
134+
if (transform) {
135+
callback(transform);
125136
}
126137
this.frameInfos[frameID].cbs.push(callback);
127138
}
128139

129140
/**
130141
* Unsubscribe from the given TF frame.
131142
*
132-
* @param {string} frameID - The TF frame to unsubscribe from.
133-
* @param {function} callback - The callback function to remove.
143+
* @param frameID - The TF frame to unsubscribe from.
144+
* @param callback - The callback function to remove.
134145
*/
135-
unsubscribe(frameID, callback) {
146+
unsubscribe(frameID: string, callback: (transform: Transform) => void) {
136147
// remove leading slash, if it's there
137148
if (frameID.startsWith("/")) {
138149
frameID = frameID.substring(1);

src/tf/ROS2TFClient.js renamed to src/tf/ROS2TFClient.ts

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,20 @@
1+
import { tf2_web_republisher } from "../types/tf2_web_republisher.js";
12
import Action from "../core/Action.js";
23
import BaseTFClient from "./BaseTFClient.js";
34

45
/**
56
* A TF Client that listens to TFs from tf2_web_republisher using ROS2 actions.
67
*/
78
export default class ROS2TFClient extends BaseTFClient {
8-
goal_id;
9-
actionClient;
10-
currentGoal;
9+
goal_id: string;
10+
actionClient: Action<
11+
tf2_web_republisher.TFSubscriptionGoal,
12+
tf2_web_republisher.TFSubscriptionResult,
13+
tf2_web_republisher.TFSubscriptionFeedback
14+
>;
15+
currentGoal: tf2_web_republisher.TFSubscriptionGoal;
1116

12-
/** @param {ConstructorParameters<typeof BaseTFClient>[0]} options */
13-
constructor(options) {
17+
constructor(options: ConstructorParameters<typeof BaseTFClient>[0]) {
1418
super(options);
1519

1620
this.goal_id = "";
@@ -44,7 +48,7 @@ export default class ROS2TFClient extends BaseTFClient {
4448
const id = this.actionClient.sendGoal(
4549
goalMessage,
4650
() => {},
47-
(feedback) => {
51+
(feedback: tf2_web_republisher.TFSubscriptionFeedback) => {
4852
this.processTFArray(feedback);
4953
},
5054
);

src/tf/TFClient.js renamed to src/tf/TFClient.ts

Lines changed: 42 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -8,35 +8,53 @@ import Goal from "../actionlib/Goal.js";
88

99
import Service from "../core/Service.js";
1010
import Topic from "../core/Topic.js";
11+
import Ros from "../core/Ros.js";
12+
import { tf2_msgs } from "../types/tf2_msgs.js";
13+
import { tf2_web_republisher } from "../types/tf2_web_republisher.js";
1114

1215
import BaseTFClient from "./BaseTFClient.js";
1316

1417
/**
1518
* A TF Client that listens to TFs from tf2_web_republisher.
1619
*/
1720
export default class TFClient extends BaseTFClient {
18-
/** @type {Goal|false} */
19-
currentGoal = false;
20-
/** @type {Topic|false} */
21-
currentTopic = false;
22-
repubServiceName;
23-
actionClient;
24-
serviceClient;
21+
currentGoal: Goal<tf2_web_republisher.TFSubscriptionGoal> | false = false;
22+
currentTopic: Topic<tf2_msgs.TFMessage> | false = false;
23+
repubServiceName: string;
24+
actionClient: ActionClient<tf2_web_republisher.TFSubscriptionGoal>;
25+
serviceClient: Service<
26+
tf2_web_republisher.RepublishTFsRequest,
27+
tf2_web_republisher.RepublishTFsResponse
28+
>;
29+
_subscribeCB: ((tf: tf2_msgs.TFMessage) => void) | undefined = undefined;
2530

2631
/**
27-
* @param {Object} options
28-
* @param {import('../core/Ros.js').default} options.ros - The ROSLIB.Ros connection handle.
29-
* @param {string} [options.fixedFrame=base_link] - The fixed frame.
30-
* @param {number} [options.angularThres=2.0] - The angular threshold for the TF republisher.
31-
* @param {number} [options.transThres=0.01] - The translation threshold for the TF republisher.
32-
* @param {number} [options.rate=10.0] - The rate for the TF republisher.
33-
* @param {number} [options.updateDelay=50] - The time (in ms) to wait after a new subscription
32+
* @param options
33+
* @param options.ros - The ROSLIB.Ros connection handle.
34+
* @param [options.fixedFrame=base_link] - The fixed frame.
35+
* @param [options.angularThres=2.0] - The angular threshold for the TF republisher.
36+
* @param [options.transThres=0.01] - The translation threshold for the TF republisher.
37+
* @param [options.rate=10.0] - The rate for the TF republisher.
38+
* @param [options.updateDelay=50] - The time (in ms) to wait after a new subscription
3439
* to update the TF republisher's list of TFs.
35-
* @param {number} [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
36-
* @param {string} [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
37-
* @param {string} [options.repubServiceName="/republish_tfs"] - The name of the republish_tfs service (non groovy compatibility mode only).
40+
* @param [options.topicTimeout=2.0] - The timeout parameter for the TF republisher.
41+
* @param [options.serverName="/tf2_web_republisher"] - The name of the tf2_web_republisher server.
42+
* @param [options.repubServiceName="/republish_tfs"] - The name of the republish_tfs service (non groovy compatibility mode only).
3843
*/
39-
constructor({ repubServiceName = "/republish_tfs", ...options }) {
44+
constructor({
45+
repubServiceName = "/republish_tfs",
46+
...options
47+
}: {
48+
ros: Ros;
49+
fixedFrame?: string;
50+
angularThres?: number;
51+
transThres?: number;
52+
rate?: number;
53+
updateDelay?: number;
54+
topicTimeout?: number;
55+
serverName?: string;
56+
repubServiceName?: string;
57+
}) {
4058
super(options);
4159

4260
this.repubServiceName = repubServiceName;
@@ -63,7 +81,7 @@ export default class TFClient extends BaseTFClient {
6381
* based on the current list of TFs.
6482
*/
6583
updateGoal() {
66-
const goalMessage = {
84+
const goalMessage: tf2_web_republisher.TFSubscriptionGoal = {
6785
source_frames: Object.keys(this.frameInfos),
6886
target_frame: this.fixedFrame,
6987
angular_thres: this.angularThres,
@@ -79,7 +97,7 @@ export default class TFClient extends BaseTFClient {
7997
if (this.currentGoal) {
8098
this.currentGoal.cancel();
8199
}
82-
this.currentGoal = new Goal({
100+
this.currentGoal = new Goal<tf2_web_republisher.TFSubscriptionGoal>({
83101
actionClient: this.actionClient,
84102
goalMessage: goalMessage,
85103
});
@@ -92,9 +110,8 @@ export default class TFClient extends BaseTFClient {
92110
* The service interface has the same parameters as the action,
93111
* plus the timeout
94112
*/
95-
goalMessage.timeout = this.topicTimeout;
96113
this.serviceClient.callService(
97-
goalMessage,
114+
{ ...goalMessage, timeout: this.topicTimeout },
98115
this.processResponse.bind(this),
99116
);
100117
}
@@ -106,9 +123,9 @@ export default class TFClient extends BaseTFClient {
106123
* Process the service response and subscribe to the tf republisher
107124
* topic.
108125
*
109-
* @param {Object} response - The service response containing the topic name.
126+
* @param response - The service response containing the topic name.
110127
*/
111-
processResponse(response) {
128+
processResponse(response: tf2_web_republisher.RepublishTFsResponse) {
112129
/*
113130
* Do not setup a topic subscription if already disposed. Prevents a race condition where
114131
* The dispose() function is called before the service call receives a response.
@@ -125,7 +142,7 @@ export default class TFClient extends BaseTFClient {
125142
this.currentTopic.unsubscribe(this._subscribeCB);
126143
}
127144

128-
this.currentTopic = new Topic({
145+
this.currentTopic = new Topic<tf2_msgs.TFMessage>({
129146
ros: this.ros,
130147
name: response.topic_name,
131148
messageType: "tf2_web_republisher/TFArray",

src/tf/index.ts

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
1-
export { default as TFClient } from "./TFClient.js";
2-
export { default as ROS2TFClient } from "./ROS2TFClient.js";
1+
export { default as TFClient } from "./TFClient";
2+
export { default as ROS2TFClient } from "./ROS2TFClient";

src/types/geometry_msgs.ts

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
export namespace geometry_msgs {
2+
export interface TransformStamped {
3+
// TODO: some sort of unholy union type of ros1 header and ros2 header???
4+
child_frame_id: string;
5+
transform: Transform;
6+
}
7+
export interface Transform {
8+
translation: Vector3;
9+
rotation: Quaternion;
10+
}
11+
export interface Vector3 {
12+
x: number;
13+
y: number;
14+
z: number;
15+
}
16+
export interface Quaternion {
17+
x: number;
18+
y: number;
19+
z: number;
20+
w: number;
21+
}
22+
}

src/types/tf2_msgs.ts

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
import { geometry_msgs } from "./geometry_msgs";
2+
3+
export namespace tf2_msgs {
4+
export interface TFMessage {
5+
transforms: geometry_msgs.TransformStamped[];
6+
}
7+
}

src/types/tf2_web_republisher.ts

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
import { geometry_msgs } from "./geometry_msgs";
2+
3+
export namespace tf2_web_republisher {
4+
export interface RepublishTFsRequest extends TFSubscriptionGoal {
5+
timeout: {
6+
sec: number;
7+
nsec: number;
8+
};
9+
}
10+
11+
export interface RepublishTFsResponse {
12+
topic_name: string;
13+
}
14+
15+
export interface TFSubscriptionGoal {
16+
source_frames: string[];
17+
target_frame: string;
18+
angular_thres: number;
19+
trans_thres: number;
20+
rate: number;
21+
}
22+
23+
export type TFSubscriptionResult = Record<never, never>;
24+
25+
export interface TFSubscriptionFeedback {
26+
transforms: geometry_msgs.TransformStamped[];
27+
}
28+
}

0 commit comments

Comments
 (0)