roslib
Version:
The standard ROS Javascript Library
200 lines (199 loc) • 9.91 kB
TypeScript
import { RosbridgeMessage, RosbridgeSetStatusLevelMessage } from '../types/protocol.ts';
import { default as Topic } from './Topic.ts';
import { default as Service } from './Service.ts';
import { default as Param } from './Param.ts';
import { default as TFClient } from '../tf/TFClient.ts';
import { default as ActionClient } from '../actionlib/ActionClient.ts';
import { default as SimpleActionServer } from '../actionlib/SimpleActionServer.ts';
import { EventEmitter } from 'eventemitter3';
import { rosapi } from '../types/rosapi.ts';
import { ITransportFactory, TransportEvent } from './transport/Transport.ts';
export interface TypeDefDict {
[key: string]: string | string[] | TypeDefDict | TypeDefDict[];
}
/**
* Manages connection to the rosbridge server and all interactions with ROS.
*
* Emits the following events:
* * 'connection' - Connected to the rosbridge server.
* * 'close' - Disconnected to the rosbridge server.
* * 'error' - There was an error with ROS.
* * <topicName> - A message came from rosbridge with the given topic name.
* * <serviceID> - A service response came from rosbridge with the given ID.
*/
export default class Ros extends EventEmitter<{
connection: [TransportEvent];
close: [TransportEvent];
error: [TransportEvent];
} & Record<string, [RosbridgeMessage]>> {
#private;
private transport?;
private transportFactory;
constructor({ url, transportFactory, }?: {
/**
* The rosbridge server URL. Can be specified later with `connect`.
* If specified, then will immediately try to connect to the server.
*/
url?: string;
/**
* The factory to use to create a transport.
* Defaults to a WebSocket transport factory.
*/
transportFactory?: ITransportFactory;
});
get isConnected(): boolean;
connect(url: string): Promise<void>;
close(): void;
private handleMessage;
/**
* Send an authorization request to the server.
*
* @param mac - MAC (hash) string given by the trusted source.
* @param client - IP of the client.
* @param dest - IP of the destination.
* @param rand - Random string given by the trusted source.
* @param t - Time of the authorization request.
* @param level - User level as a string given by the client.
* @param end - End time of the client's session.
*/
authenticate(mac: string, client: string, dest: string, rand: string, t: number, level: string, end: number): void;
/**
* Sends the message to the transport.
* If not connected, queues the message to send once reconnected.
*/
callOnConnection(message: RosbridgeMessage): void;
/**
* Send a set_level request to the server.
*
* @param level - Status level (none, error, warning, info).
* @param [id] - Operation ID to change status level on.
*/
setStatusLevel(level: RosbridgeSetStatusLevelMessage["level"], id?: string): void;
/**
* Retrieve a list of action servers in ROS as an array of string.
*
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getActionServers(callback: (actionservers: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of topics in ROS as an array.
*
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getTopics(callback: (result: rosapi.TopicsResponse) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of topics in ROS as an array of a specific type.
*
* @param topicType - The topic type to find.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getTopicsForType(topicType: string, callback: (topics: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of active service names in ROS.
*
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getServices(callback: (services: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of services in ROS as an array as specific type.
*
* @param serviceType - The service type to find.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getServicesForType(serviceType: string, callback: (services: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve the details of a ROS service request.
*
* @param type - The type of the service.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getServiceRequestDetails(type: string, callback: (result: rosapi.ServiceRequestDetailsResponse) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve the details of a ROS service response.
*
* @param type - The type of the service.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getServiceResponseDetails(type: string, callback: (result: rosapi.ServiceResponseDetailsResponse) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of active node names in ROS.
*
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getNodes(callback: (result: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of subscribed topics, publishing topics and services of a specific node.
*
* @param node - Name of the node.
*/
getNodeDetails(node: string, callback: (result: rosapi.NodeDetailsResponse) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve a list of parameter names from the ROS Parameter Server.
*
* @param callback - Function with the following params:
* @param failedCallback - The callback function when the service call failed with params:
*/
getParams(callback: (names: string[]) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve the type of a ROS topic.
*
* @param topic - Name of the topic.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getTopicType(topic: string, callback: (type: string) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve the type of a ROS service.
*
* @param service - Name of the service.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getServiceType(service: string, callback: (type: string) => void, failedCallback?: (error: string) => void): void;
/**
* Retrieve the details of a ROS message.
*
* @param message - The name of the message type.
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getMessageDetails(message: string, callback: (typedefs: rosapi.TypeDef[]) => void, failedCallback?: (error: string) => void): void;
/**
* Decode a typedef array into a dictionary like `rosmsg show foo/bar`.
*
* @param defs - Array of type_def dictionary.
*/
decodeTypeDefs(defs: rosapi.TypeDef[]): TypeDefDict;
/**
* @callback getTopicsAndRawTypesCallback
* @param {Object} result - The result object with the following params:
* @param {string[]} result.topics - Array of topic names.
* @param {string[]} result.types - Array of message type names.
* @param {string[]} result.typedefs_full_text - Array of full definitions of message types, similar to `gendeps --cat`.
*/
/**
* @callback getTopicsAndRawTypesFailedCallback
* @param {string} error - The error message reported by ROS.
*/
/**
* Retrieve a list of topics and their associated type definitions.
*
* @param callback - Function with the following params:
* @param [failedCallback] - The callback function when the service call failed with params:
*/
getTopicsAndRawTypes(callback: (result: rosapi.TopicsAndRawTypesResponse) => void, failedCallback?: (error: string) => void): void;
Topic<T>(options: Omit<ConstructorParameters<typeof Topic<T>>[0], "ros">): Topic<T>;
Param<T>(options: Omit<ConstructorParameters<typeof Param<T>>[0], "ros">): Param<T>;
Service<TRequest, TResponse>(options: Omit<ConstructorParameters<typeof Service<TRequest, TResponse>>[0], "ros">): Service<TRequest, TResponse>;
TFClient(options: Omit<ConstructorParameters<typeof TFClient>[0], "ros">): TFClient;
ActionClient<TGoal, TFeedback, TResult>(options: Omit<ConstructorParameters<typeof ActionClient<TGoal, TFeedback, TResult>>[0], "ros">): ActionClient<TGoal, TFeedback, TResult>;
SimpleActionServer<TGoal, TFeedback, TResult>(options: Omit<ConstructorParameters<typeof SimpleActionServer<TGoal, TFeedback, TResult>>[0], "ros">): SimpleActionServer<TGoal, TFeedback, TResult>;
}