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

List of all members.

Classes

class  MessageListenerForwarding< MessageType >
interface  PacketHandler

Public Member Functions

byte[] constructMessage (int id, org.ros.message.Message m)
TopicInfo[] getPublications ()
TopicInfo[] getSubscriptions ()
void negotiateTopics ()
boolean parsePacket (int topic_id, byte[] msg_data)
 Protocol (Node nh, PacketHandler handler)
void setOnNewPublication (TopicRegistrationListener listener)
void setOnNewSubcription (TopicRegistrationListener listener)
void start ()

Static Public Attributes

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

Package Attributes

ParameterTree paramT
TimerTask timer_cb

Static Package Attributes

static final int CONNECTION_TIMOUT_PERIOD = 10000
static final int TOPIC_PUBLISHERS = 0
static final int TOPIC_SUBSCRIBERS = 1
static final int TOPIC_TIME = 10

Private Member Functions

void addTopic (TopicInfo topic, boolean is_publisher)
void handleLogging (byte[] msg_data)
void handleParameterRequest (byte[] msg_data)

Private Attributes

boolean connected = false
Timer connection_timer = new Timer()
Map< Integer, TopicInfoid_to_topic = new HashMap<Integer, TopicInfo>()
Map< Integer, MessageDeserializer > msg_deserializers = new HashMap<Integer, MessageDeserializer>()
TopicRegistrationListener newPubListener
TopicRegistrationListener newSubListener
Node node
PacketHandler packetHandler
Map< Integer, Publisher > publishers = new HashMap<Integer, Publisher>()
Map< Integer, Subscriber > subscribers = new HashMap<Integer, Subscriber>()
boolean sync_requested = false
Map< String, Integer > topic_to_id = new HashMap<String, Integer>()

Detailed Description

Protocol handler for rosserial.

Author:
Adam Stambler

Definition at line 59 of file Protocol.java.


Constructor & Destructor Documentation

org.ros.rosserial.Protocol.Protocol ( Node  nh,
PacketHandler  handler 
) [inline]

Definition at line 114 of file Protocol.java.


Member Function Documentation

void org.ros.rosserial.Protocol.addTopic ( TopicInfo  topic,
boolean  is_publisher 
) [inline, private]

! Registers a topic being transmitted over the serial port /param topic- The topic info msg describing the topic /param is_publisher - is the device on the other end of the serial line publishing

Definition at line 169 of file Protocol.java.

byte [] org.ros.rosserial.Protocol.constructMessage ( int  id,
org.ros.message.Message  m 
) [inline]

Construct a valid protocol message. This take the id and m, serializes them and return the raw bytes to be sent

Definition at line 149 of file Protocol.java.

Definition at line 216 of file Protocol.java.

Definition at line 206 of file Protocol.java.

void org.ros.rosserial.Protocol.handleLogging ( byte[]  msg_data) [inline, private]

Handle Logging takes the log message from rosserial and rebroadcasts it via rosout at the appropriate logging level

Parameters:
msg_data

Definition at line 327 of file Protocol.java.

void org.ros.rosserial.Protocol.handleParameterRequest ( byte[]  msg_data) [inline, private]

Definition at line 351 of file Protocol.java.

Ask the remote endpoint for any topics it wants to publish or subscribe to.

Definition at line 141 of file Protocol.java.

boolean org.ros.rosserial.Protocol.parsePacket ( int  topic_id,
byte[]  msg_data 
) [inline]

Parse a packet from the remote endpoint.

Parameters:
topic_idID of the message topic.
msg_dataThe data for the message.
Returns:

Definition at line 267 of file Protocol.java.

Set a new topic registration listener for publications.

Parameters:
listener

Definition at line 125 of file Protocol.java.

Set a new topic registration listener for subscriptions.

Parameters:
listener

Definition at line 134 of file Protocol.java.

Definition at line 253 of file Protocol.java.


Member Data Documentation

boolean org.ros.rosserial.Protocol.connected = false [private]

Definition at line 251 of file Protocol.java.

Timer org.ros.rosserial.Protocol.connection_timer = new Timer() [private]

This timer handles monitoring handles monitoring the connection to the device;

Definition at line 230 of file Protocol.java.

final int org.ros.rosserial.Protocol.CONNECTION_TIMOUT_PERIOD = 10000 [static, package]

Definition at line 231 of file Protocol.java.

Map<Integer, TopicInfo> org.ros.rosserial.Protocol.id_to_topic = new HashMap<Integer, TopicInfo>() [private]

Map of IDs being sent down the channel to the topics they represent.

Definition at line 77 of file Protocol.java.

Map<Integer, MessageDeserializer> org.ros.rosserial.Protocol.msg_deserializers = new HashMap<Integer, MessageDeserializer>() [private]

Topic ID to message deserializer for the associated topic message.

Definition at line 97 of file Protocol.java.

final byte [] org.ros.rosserial.Protocol.NEGOTIATE_TOPICS_REQUEST = { (byte) 0, (byte) 0, (byte) 0, (byte) 0 } [static]

Definition at line 67 of file Protocol.java.

Listener for new publisher registrations.

Definition at line 102 of file Protocol.java.

Listener for new subscriber registrations.

Definition at line 107 of file Protocol.java.

Node hosting the subscribers and publishers.

Definition at line 72 of file Protocol.java.

Handles wire communication to the remote endpoint.

Definition at line 112 of file Protocol.java.

ParameterTree org.ros.rosserial.Protocol.paramT [package]

Definition at line 350 of file Protocol.java.

Map<Integer, Publisher> org.ros.rosserial.Protocol.publishers = new HashMap<Integer, Publisher>() [private]

Topic ID to publisher.

Definition at line 87 of file Protocol.java.

Map<Integer, Subscriber> org.ros.rosserial.Protocol.subscribers = new HashMap<Integer, Subscriber>() [private]

Topic ID to subscriber.

Definition at line 92 of file Protocol.java.

boolean org.ros.rosserial.Protocol.sync_requested = false [private]

Definition at line 250 of file Protocol.java.

Initial value:
 new TimerTask() {
                
                @Override
                public void run() {
                        
                        if (sync_requested){
                                connected = true;
                                sync_requested = false;
                                
                        }
                        else{
                                node.getLog().info("Connection to client lost. Topic negotiation requested");
                                connected = false;
                                negotiateTopics();
                        }
                }
        }

Definition at line 232 of file Protocol.java.

final int org.ros.rosserial.Protocol.TOPIC_PUBLISHERS = 0 [static, package]

Definition at line 63 of file Protocol.java.

final int org.ros.rosserial.Protocol.TOPIC_SUBSCRIBERS = 1 [static, package]

Definition at line 64 of file Protocol.java.

final int org.ros.rosserial.Protocol.TOPIC_TIME = 10 [static, package]

Definition at line 65 of file Protocol.java.

Map<String, Integer> org.ros.rosserial.Protocol.topic_to_id = new HashMap<String, Integer>() [private]

Map of topic names to the IDs being sent down the channel for them.

Definition at line 82 of file Protocol.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