11import Transform from "../math/Transform.js" ;
22import { 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 */
79export 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 ) ;
0 commit comments