roslib
Version:
The standard ROS Javascript Library
72 lines (71 loc) • 2.72 kB
TypeScript
import { default as Transform } from '../math/Transform.ts';
import { default as Ros } from '../core/Ros.ts';
import { tf2_msgs } from '../types/tf2_msgs.ts';
import { std_msgs } from '../types/std_msgs.ts';
/**
* Base class for TF Clients that provides common functionality.
*/
export default class BaseTFClient {
frameInfos: Record<string, {
transform?: Transform;
cbs: ((tf: Transform) => void)[];
}>;
republisherUpdateRequested: boolean;
ros: Ros;
fixedFrame: string;
angularThres: number;
transThres: number;
rate: number;
updateDelay: number;
topicTimeout: std_msgs.time;
serverName: string;
/**
* @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 [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, fixedFrame, angularThres, transThres, rate, updateDelay, topicTimeout, serverName, }: {
ros: Ros;
fixedFrame?: string;
angularThres?: number;
transThres?: number;
rate?: number;
updateDelay?: number;
topicTimeout?: number;
serverName?: string;
});
/**
* Process the incoming TF message and send them out using the callback
* functions.
*
* @param tf - The TF message from the server.
*/
processTFArray(tf: tf2_msgs.TFMessage): void;
/**
* Create and send a new goal (or service request) to the tf2_web_republisher
* based on the current list of TFs.
* This method should be overridden by subclasses.
*/
updateGoal(): void;
/**
* Subscribe to the given TF frame.
*
* @param frameID - The TF frame to subscribe to.
* @param callback - Function with the following params:
*/
subscribe(frameID: string, callback: (transform: Transform) => void): void;
/**
* Unsubscribe from the given TF frame.
*
* @param frameID - The TF frame to unsubscribe from.
* @param [callback] - The callback function to remove.
*/
unsubscribe(frameID: string, callback?: (transform: Transform) => void): void;
}