roslib
Version:
The standard ROS Javascript Library
96 lines (95 loc) • 3.72 kB
TypeScript
import { EventEmitter } from 'eventemitter3';
import { default as Ros } from './Ros.ts';
import { RosbridgeAdvertiseMessage, RosbridgeSubscribeMessage } from '../types/protocol.ts';
/**
* Publish and/or subscribe to a topic in ROS.
*
* Emits the following events:
* * 'warning' - If there are any warning during the Topic creation.
* * 'message' - The message data from rosbridge.
*/
export default class Topic<T = unknown> extends EventEmitter<{
message: [T];
warning: [string];
unsubscribe: undefined;
unadvertise: undefined;
}> {
#private;
waitForReconnect: boolean;
reconnectFunc: (() => void) | undefined;
isAdvertised: boolean;
ros: Ros;
name: string;
messageType: string;
compression: string;
throttle_rate: number;
latch: boolean;
queue_size: number;
queue_length: number;
reconnect_on_close: boolean;
callForSubscribeAndAdvertise: (message: RosbridgeSubscribeMessage | RosbridgeAdvertiseMessage) => void;
subscribeId: string | null;
advertiseId?: string;
/**
* @param options
* @param options.ros - The ROSLIB.Ros connection handle.
* @param options.name - The topic name, like '/cmd_vel'.
* @param options.messageType - The message type, like 'std_msgs/String'.
* @param [options.compression=none] - The type of compression to use, like 'png', 'cbor', or 'cbor-raw'.
* @param [options.throttle_rate=0] - The rate (in ms in between messages) at which to throttle the topics.
* @param [options.queue_size=100] - The queue created at bridge side for re-publishing webtopics.
* @param [options.latch=false] - Latch the topic when publishing.
* @param [options.queue_length=0] - The queue length at bridge side used when subscribing.
* @param [options.reconnect_on_close=true] - The flag to enable resubscription and readvertisement on close event.
*/
constructor({ ros, name, messageType, compression, throttle_rate, latch, queue_size, queue_length, reconnect_on_close, }: {
ros: Ros;
name: string;
messageType: string;
compression?: string;
throttle_rate?: number;
queue_size?: number;
latch?: boolean;
queue_length?: number;
reconnect_on_close?: boolean;
});
/**
* Every time a message is published for the given topic, the callback
* will be called with the message object.
*
* @param callback - Function with the following params:
*/
subscribe(callback: (message: T) => void): void;
/**
* Unregister as a subscriber for the topic. Unsubscribing will stop
* and remove all subscribe callbacks. To remove a callback, you must
* explicitly pass the callback function in.
*
* @param [callback] - The callback to unregister, if
* provided and other listeners are registered the topic won't
* unsubscribe, just stop emitting to the passed listener.
*/
unsubscribe(callback?: Parameters<EventEmitter["off"]>[1]): void;
/**
* Register as a publisher for the topic.
*/
advertise(): void;
/**
* Unregister as a publisher for the topic.
*/
unadvertise(): void;
/**
* Publish the message.
*
* @param message - The message to publish.
*/
publish(message: T): void;
/**
* Retrieves list of publishers for this topic.
*
* @param callback - Function with the following params:
* * publishers - The list of publishers.
* @param [failedCallback] - The callback function when the service call failed.
*/
getPublishers(callback: (publishers: string[]) => void, failedCallback?: (error: string) => void): void;
}