Class ZOROSBridgeConnection
Inheritance
Inherited Members
Namespace: ZO.ROS
Assembly: Unity.ZeroSim.dll
Syntax
public class ZOROSBridgeConnection
Properties
| Improve this Doc View SourceHostname
Hostname or IP addresss
Declaration
public string Hostname { get; set; }
Property Value
Type | Description |
---|---|
System.String |
Instance
Declaration
public static ZOROSBridgeConnection Instance { get; }
Property Value
Type | Description |
---|---|
ZOROSBridgeConnection |
IsConnected
Checks if the ROS Bridge is connected.
Declaration
public bool IsConnected { get; }
Property Value
Type | Description |
---|---|
System.Boolean |
Port
TCP Port. Do not recommend changing.
Declaration
public int Port { get; set; }
Property Value
Type | Description |
---|---|
System.Int32 |
Serialization
Declaration
public ZOROSBridgeConnection.SerializationType Serialization { get; set; }
Property Value
Type | Description |
---|---|
ZOROSBridgeConnection.SerializationType |
Methods
| Improve this Doc View SourceAdvertise(String, String, String)
Advertise a ROS message topic.
Declaration
public void Advertise(string topic, string type, string id = "zero_sim_unity")
Parameters
Type | Name | Description |
---|---|---|
System.String | topic | ROS topic. For example: "/cmd_vel" |
System.String | type | ROS message type. For example "geometry_msgs/Twist" |
System.String | id | ROS node id. Default "zero_sim_unity" |
AdvertiseService<T>(String, String, Func<ZOROSBridgeConnection, ZOROSMessageInterface, String, Task>)
Advertises an external ROS service server. Requests come to the client via Call Service.
Declaration
public void AdvertiseService<T>(string service, string type, Func<ZOROSBridgeConnection, ZOROSMessageInterface, string, Task> serviceRequest)
where T : ZOROSMessageInterface
Parameters
Type | Name | Description |
---|---|---|
System.String | service | The name of the service to advertise. |
System.String | type | The advertised service message type. |
System.Func<ZOROSBridgeConnection, ZOROSMessageInterface, System.String, System.Threading.Tasks.Task> | serviceRequest |
Type Parameters
Name | Description |
---|---|
T |
CallService<T, R>(T, String, String, Func<ZOROSBridgeConnection, ZOROSMessageInterface, Task>)
Call ROS service.
Declaration
public void CallService<T, R>(T calling_message, string service, string id, Func<ZOROSBridgeConnection, ZOROSMessageInterface, Task> serviceCallResponse)
where T : ZOROSMessageInterface where R : ZOROSMessageInterface
Parameters
Type | Name | Description |
---|---|---|
T | calling_message | The calling message |
System.String | service | Service name |
System.String | id | Unique ID. Important to be Unique! |
System.Func<ZOROSBridgeConnection, ZOROSMessageInterface, System.Threading.Tasks.Task> | serviceCallResponse | Callback when service responds |
Type Parameters
Name | Description |
---|---|
T | Service call message type |
R | Service response message type |
ConnectAsync()
Asynchronously connect to ROS Bridge server.
Declaration
public Task ConnectAsync()
Returns
Type | Description |
---|---|
System.Threading.Tasks.Task | Task |
Examples
// run async task. if cannot connect wait for a couple of seconds and try again
Task rosBridgeConnectionTask = Task.Run(async () => {
await _rosBridgeConnection.ConnectAsync();
});
|
Improve this Doc
View Source
Publish<T>(T, String, String)
Publish message to topic.
Declaration
public void Publish<T>(T message, string topic, string id = "zero_sim_unity")
where T : ZOROSMessageInterface
Parameters
Type | Name | Description |
---|---|---|
T | message | ROS Message type |
System.String | topic | ROS Topic |
System.String | id | Unique ID of sender. |
Type Parameters
Name | Description |
---|---|
T | ROS Message derived from ZOROSMessageInterface |
SendBSON(JObject)
Declaration
public void SendBSON(JObject json)
Parameters
Type | Name | Description |
---|---|---|
Newtonsoft.Json.Linq.JObject | json |
SendBSON(Byte[])
Declaration
public void SendBSON(byte[] byteArray)
Parameters
Type | Name | Description |
---|---|---|
System.Byte[] | byteArray |
SendBSON(MemoryStream)
Declaration
public void SendBSON(MemoryStream memoryStream)
Parameters
Type | Name | Description |
---|---|---|
System.IO.MemoryStream | memoryStream |
SendBSONAsync(JObject)
Declaration
public Task SendBSONAsync(JObject json)
Parameters
Type | Name | Description |
---|---|---|
Newtonsoft.Json.Linq.JObject | json |
Returns
Type | Description |
---|---|
System.Threading.Tasks.Task |
SendBSONAsync(Byte[])
Declaration
public Task SendBSONAsync(byte[] byteArray)
Parameters
Type | Name | Description |
---|---|---|
System.Byte[] | byteArray |
Returns
Type | Description |
---|---|
System.Threading.Tasks.Task |
SendBSONAsync(MemoryStream)
Declaration
public Task SendBSONAsync(MemoryStream memoryStream)
Parameters
Type | Name | Description |
---|---|---|
System.IO.MemoryStream | memoryStream |
Returns
Type | Description |
---|---|
System.Threading.Tasks.Task |
SendJSONString(String)
Declaration
public void SendJSONString(string message)
Parameters
Type | Name | Description |
---|---|---|
System.String | message |
SendJSONStringAsync(String)
Declaration
public Task SendJSONStringAsync(string message)
Parameters
Type | Name | Description |
---|---|---|
System.String | message |
Returns
Type | Description |
---|---|
System.Threading.Tasks.Task |
ServiceResponse<T>(T, String, Boolean, String)
Send a response to a service call. NOTE: id parameter is very important.
Declaration
public void ServiceResponse<T>(T response_message, string service, bool result, string id)
where T : ZOROSMessageInterface
Parameters
Type | Name | Description |
---|---|---|
T | response_message | the return values. If the service had no return values, then this field can be omitted (and will be by the rosbridge server) |
System.String | service | the name of the service that was called |
System.Boolean | result | |
System.String | id | if an ID was provided to the service request, then the service response will contain the ID |
Type Parameters
Name | Description |
---|---|
T | Response message |
Stop()
Stops ROS Bridge TCP Connection.
Declaration
public void Stop()
Subscribe<T>(String, String, String, Func<ZOROSBridgeConnection, ZOROSMessageInterface, Task>)
This command subscribes the client to the specified topic. It is recommended that if the client has multiple components subscribing to the same topic, that each component makes its own subscription request providing an ID. That way, each can individually unsubscribe and rosbridge can select the correct rate at which to send messages.
type – the (expected) type of the topic to subscribe to. If left off, type will be inferred, and if the topic doesn't exist then the command to subscribe will fail topic – the name of the topic to subscribe to throttle_rate – the minimum amount of time (in ms) that must elapse between messages being sent. Defaults to 0 queue_length – the size of the queue to buffer messages. Messages are buffered as a result of the throttle_rate. Defaults to 1. id – if specified, then this specific subscription can be unsubscribed by referencing the ID. fragment_size – the maximum size that a message can take before it is to be fragmented. compression – an optional string to specify the compression scheme to be used on messages. Valid values are "none" and "png"
If queue_length is specified, then messages are placed into the queue before being sent. Messages are sent from the head of the queue. If the queue gets full, the oldest message is removed and replaced by the newest message.
If a client has multiple subscriptions to the same topic, then messages are sent at the lowest throttle_rate, with the lowest fragmentation size, and highest queue_length. It is recommended that the client provides IDs for its subscriptions, to enable rosbridge to effectively choose the appropriate fragmentation size and publishing rate.
Declaration
public void Subscribe<T>(string id, string topic, string type, Func<ZOROSBridgeConnection, ZOROSMessageInterface, Task> subscriptionCallback)
where T : ZOROSMessageInterface
Parameters
Type | Name | Description |
---|---|---|
System.String | id | f specified, then this specific subscription can be unsubscribed by referencing the ID. |
System.String | topic | the name of the topic to subscribe to |
System.String | type | ROS message type |
System.Func<ZOROSBridgeConnection, ZOROSMessageInterface, System.Threading.Tasks.Task> | subscriptionCallback | Called when message is received. |
Type Parameters
Name | Description |
---|---|
T | ZOROSMessageInterface |
UnAdvertise(String)
Unadvertise a ROS message topic.
Declaration
public void UnAdvertise(string topic)
Parameters
Type | Name | Description |
---|---|---|
System.String | topic |
UnAdvertiseService(String)
Stops advertising an external ROS service server
Declaration
public void UnAdvertiseService(string service)
Parameters
Type | Name | Description |
---|---|---|
System.String | service | the name of the service to unadvertise |
Unsubscribe(String, String)
Unsubscribe a ROS message topic.
Declaration
public void Unsubscribe(string id, string topic)
Parameters
Type | Name | Description |
---|---|---|
System.String | id | |
System.String | topic |
Events
| Improve this Doc View Source_disconnectEvent
Declaration
public event ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler _disconnectEvent
Event Type
Type | Description |
---|---|
ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler |
ROSBridgeConnectEvent
Event that is called when connected to ROS bridge.
Declaration
public event ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler ROSBridgeConnectEvent
Event Type
Type | Description |
---|---|
ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler |
ROSBridgeDisconnectEvent
Event called when disconnected from ROS Bridge
Declaration
public event ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler ROSBridgeDisconnectEvent
Event Type
Type | Description |
---|---|
ZOROSBridgeConnection.ROSBridgeConnectionChangeHandler |