Skip to content

Latest commit

 

History

History
 
 

docs

Folders and files

NameName
Last commit message
Last commit date

parent directory

..
 
 

API

Ros

Method Details
Constructor
import { Ros } from '@robostack/roslib';
const ros = new Ros(options);
Available options:
  • url(optional) - (can be specified later with `connect`) the WebSocket URL for rosbridge or the node server url to connect using socket.io (if socket.io exists in the page)
  • transportLibrary (optional) - one of '[websocket]', 'workersocket' (default), 'socket.io' or RTCPeerConnection instance controlling how the connection is created in `connect`.
  • transportOptions (optional) - the options to use use when creating a connection. Currently only used if `transportLibrary` is RTCPeerConnection.
.connect(url: string): void Connect to the specified WebSocket.
  • url - WebSocket URL or RTCDataChannel label for Rosbridge
.close(): void Disconnect from the WebSocket server.
.authenticate( mac: string, client: string, dest: string, rand: string, t: number, level: string, end: number, ): void Sends an authorization request to the server.
  • mac - MAC (hash) string given by the trusted source.
  • client - IP of the client.
  • dest - IP of the destination.
  • rand - Random string given by the trusted source.
  • t - Time of the authorization request.
  • level - User level as a string given by the client.
  • end - End time of the client's session.
.callOnConnection(message: any): void Sends the message over the WebSocket, but queues the message up if not yet connected.
setStatusLevel(level, id: number): void Sends a set_level request to the server
  • level - Status level (none, error, warning, info)
  • id(optional) - Operation ID to change status level on
.getActionServers(callback, failedCallback): void Retrieves Action Servers in ROS as an array of string
Callback will receive an array of action server names
failedCallback will receive the error message reported by ROS
.getTopics(callback, failedCallback): void Retrieves list of topics in ROS as an array.
Callback response
  • topics - Array of topic names
  • types - Array of message type names
failedCallback will receive the error message reported by ROS
.getTopicsForType(topicType, callback, failedCallback): void Retrieves Topics in ROS as an array as specific type.
  • topicType - topic type to find
  • callback receives an array of topic names
  • failedCallback will receive the error message reported by ROS
.getServices(callback, failedCallback): void Retrieves list of active service names in ROS.
Callback will receive the array of service names
failedCallback will receive the error message reported by ROS
.getServicesForType(serviceType, callback, failedCallback): void Retrieves services in ROS as an array.
  • serviceType - service type to find
  • callback receives an array of service names
  • failedCallback will receive the error message reported by ROS
.getServiceRequestDetails(type, callback, failedCallback): void Retrieves a detail of ROS service request.
Callback will receive the service type
failedCallback will receive the error message reported by ROS
.getServiceResponseDetails(type, callback, failedCallback): void Retrieves a detail of ROS service response.
Callback will receive the service type
failedCallback will receive the error message reported by ROS
.getNodes(callback, failedCallback): void Retrieves list of active node names in ROS.
Callback will receive an array of node names
failedCallback will receive the error message reported by ROS
.getNodeDetails(nodeName, callback, failedCallback): void Retrieves list of subscribed topics, publishing topics and services of a node with the given name
Callback response
  • publications - array of published topic names
  • subscriptions - array of subscribed topic names
  • services - array of service names hosted
failedCallback will receive the error message reported by ROS
.getParams(callback, failedCallback): void Retrieves list of param names from the ROS Parameter Server.
Callback will receive the array of param names
failedCallback will receive the error message reported by ROS
.getTopicType(topicName, callback, failedCallback): void Retrieves a type of ROS topic.
Callback will receive the string for topic type failedCallback will receive the error message reported by ROS
.getServiceType(serviceName, callback, failedCallback): void Retrieves a type of ROS service.
Callback will receive the string for service type failedCallback will receive the error message reported by ROS
.getMessageDetails(topicType, callback, failedCallback): void Retrieves a detail of ROS message.
Callback will receive the array of message detail failedCallback will receive the error message reported by ROS
.decodeTypeDefs(defs): dict Decode a typedefs into a dictionary like `rosmsg show foo/bar`. Calls itself recursively to resolve type definition using hints.
  • defs - array of type_def dictionary
  • dict - Decoded typedef dictionary
.getTopicsAndRawTypes(callback, failedCallback): void Retrieves list of topics and their associated type definitions. Callback response
  • topics - Array of topic names
  • types - Array of message type names
  • typedefs_full_text - Array of full definitions of message types, similar to `gendeps --cat`
failedCallback will receive the error message reported by ROS

Message

Method Details
Constructor
import { Message } from '@robostack/roslib';
const ros = new Message(data);
Message objects are used for publishing and subscribing to and from topics.
`data` - object matching the fields defined in the .msg definition file

Param

Method Details
Constructor
import { Param } from '@robostack/roslib';
const ros = new Param(options);
Available options:
  • ros - the ROSLIB.Ros connection handle
  • name - the param name, like max_vel_x
.get(callback: (value: any) => void): void Fetches the value of the param in ROS.
The callback function will receive the value of the Ros Param
.set(value, callback: (response: any) => void): void Sets the value of the param in ROS.
The callback function will be called after the value of the Ros Param is set
.delete(callback: (response: any) => void): void Delete this parameter on the ROS server.
The callback function will be called after the value of the Ros Param is deleted

Service

Method Details
Constructor
import { Service } from '@robostack/roslib';
const ros = new Service(options);
Available options:
  • ros - the ROSLIB.Ros connection handle
  • name - the service name, like /add_two_ints
  • serviceType - the service type, like 'rospy_tutorials/AddTwoInts'
.callService(request: ServiceRequest, callback: (response: any) => void, failedCallback?: (error: any) => void): void Calls the service. Returns the service response in the callback. Does nothing if this service is currently advertised.
  • request - the ROSLIB.ServiceRequest to send
  • callback - Function with the response from the service request
  • failedCallback(optional) - the callback function when the service call failed. Invoked with the error message reported by ROS
.advertise(callback: (request: any, response: any) => void): void Advertise the service. This turns the Service object from a client into a server.
The callback will receive every request that's made on this service.
  • request - the ROSLIB.ServiceRequest to send
  • response - It should return true if the service has finished successfully, i.e. without any fatal errors.
.unadvertise(): void Unadvertise the service.

Topic

Method Details
Constructor
import { Topic } from '@robostack/roslib';
const topic = new Topic(options);
Available options:
  • ros - the `Ros` connection handle
  • name - the topic name, like /cmd_vel
  • messageType - the message type, like 'std_msgs/String'
  • compression - the type of compression to use, like 'png', 'cbor', or 'cbor-raw'
  • throttle_rate - the rate (in ms in between messages) at which to throttle the topics
  • queue_size - the queue created at bridge side for re-publishing webtopics (defaults to 100)
  • latch - latch the topic when publishing
  • queue_length - the queue length at bridge side used when subscribing (defaults to 0, no queueing).
  • reconnect_on_close - the flag to enable resubscription and readvertisement on close event(defaults to true).
.subscribe(callback: (RosMessage) => void): void Every time a message is published for the given topic, the callback will receive the message object.
.unsubscribe(callback: (RosMessage) => void): void Unregisters as a subscriber for the topic. Unsubscribing stop remove all subscribe callbacks. To remove a call back, you must explicitly pass the callback function in
.advertise(): void Registers as a publisher for the topic.
.unadvertise(): void Unregisters as a publisher for the topic.
.publish(RosMessage): void Publish the message. The library does not validate the schema of the published message data