Classes | Public Member Functions | Static Public Attributes | Package Attributes | Private Member Functions | Private Attributes | Static Private Attributes
org.ros.rosserial.ROSSerial Class Reference

List of all members.

Classes

enum  PACKET_STATE

Public Member Functions

TopicInfo[] getPublications ()
TopicInfo[] getSubscriptions ()
 ROSSerial (Node nh, InputStream input, OutputStream output)
void run ()
void setOnNewPublication (TopicRegistrationListener listener)
void setOnNewSubcription (TopicRegistrationListener listener)
void shutdown ()

Static Public Attributes

static final byte[] FLAGS = { (byte) 0xff, (byte) 0xff }

Package Attributes

Timer packet_timeout_timer
Protocol.PacketHandler sendHandler

Private Member Functions

boolean handleByte (byte b)
void resetPacket ()

Private Attributes

int byte_index = 0
byte[] data = new byte[MAX_MSG_DATA_SIZE]
int data_len = 0
byte[] header = new byte[4]
InputStream istream
Node node
OutputStream ostream
PACKET_STATE packet_state
Protocol protocol
boolean running = false

Static Private Attributes

static final int MAX_MSG_DATA_SIZE = 512

Detailed Description

The host computer endpoint for a rosserial connection.

Author:
Adam Stambler

Definition at line 49 of file ROSSerial.java.


Constructor & Destructor Documentation

org.ros.rosserial.ROSSerial.ROSSerial ( Node  nh,
InputStream  input,
OutputStream  output 
) [inline]

Definition at line 149 of file ROSSerial.java.


Member Function Documentation

Definition at line 104 of file ROSSerial.java.

Definition at line 100 of file ROSSerial.java.

boolean org.ros.rosserial.ROSSerial.handleByte ( byte  b) [inline, private]

Definition at line 234 of file ROSSerial.java.

void org.ros.rosserial.ROSSerial.resetPacket ( ) [inline, private]

Definition at line 223 of file ROSSerial.java.

Start running the endpoint.

Definition at line 175 of file ROSSerial.java.

Set a new topic registration listener for publications.

Parameters:
listener

Definition at line 86 of file ROSSerial.java.

Set a new topic registration listener for subscriptions.

Parameters:
listener

Definition at line 95 of file ROSSerial.java.

Shut this endpoint down.

Definition at line 161 of file ROSSerial.java.


Member Data Documentation

Definition at line 122 of file ROSSerial.java.

byte [] org.ros.rosserial.ROSSerial.data = new byte[MAX_MSG_DATA_SIZE] [private]

Definition at line 120 of file ROSSerial.java.

Definition at line 121 of file ROSSerial.java.

final byte [] org.ros.rosserial.ROSSerial.FLAGS = { (byte) 0xff, (byte) 0xff } [static]

Flags for marking beginning of packet transmission

Definition at line 53 of file ROSSerial.java.

byte [] org.ros.rosserial.ROSSerial.header = new byte[4] [private]

Definition at line 119 of file ROSSerial.java.

InputStream org.ros.rosserial.ROSSerial.istream [private]

Input stream for the serial line used for communication.

Definition at line 69 of file ROSSerial.java.

final int org.ros.rosserial.ROSSerial.MAX_MSG_DATA_SIZE = 512 [static, private]

Maximum size for the incomming message data in bytes Same as Message out buffer size in rosserial_arduino

Definition at line 59 of file ROSSerial.java.

The node which is hosting the publishers and subscribers.

Definition at line 74 of file ROSSerial.java.

OutputStream org.ros.rosserial.ROSSerial.ostream [private]

Output stream for the serial line used for communication.

Definition at line 64 of file ROSSerial.java.

Definition at line 116 of file ROSSerial.java.

This timer watches when a packet starts. If the packet does not complete itself within 30 milliseconds the message is thrown away.

Definition at line 170 of file ROSSerial.java.

Protocol handler being used for this connection.

Definition at line 79 of file ROSSerial.java.

boolean org.ros.rosserial.ROSSerial.running = false [private]

True if this endpoint is running, false otherwise.

Definition at line 111 of file ROSSerial.java.

Protocol.PacketHandler org.ros.rosserial.ROSSerial.sendHandler [package]
Initial value:
 new Protocol.PacketHandler() {

                @Override
                public void send(byte[] data) {
                        
                        int chk = 0;
                        for (int i = 0; i < data.length; i++)
                                chk += 0xff & data[i];
                        chk = 255 - chk % 256;

                        try {
                                ostream.write(FLAGS);
                                ostream.write(data);
                                ostream.write((byte) chk);
                        } catch (IOException e) {
                                System.out.println("Exception sending :"
                                                + BinaryUtils.byteArrayToHexString(data));
                                e.printStackTrace();
                        }
                }
        }

Packet handler for writing to the other endpoint.

Definition at line 127 of file ROSSerial.java.


The documentation for this class was generated from the following file:


rosserial_java
Author(s): Adam Stambler
autogenerated on Thu Nov 28 2013 11:51:40