trikRuntime
trikTelemetry::Connection Class Reference

Connection class accepts requests for sensors configuration and current sensor values. More...

#include <connection.h>

Inheritance diagram for trikTelemetry::Connection:
Collaboration diagram for trikTelemetry::Connection:

Public Member Functions

 Connection (trikControl::BrickInterface &brick)
 Constructor. More...
 
- Public Member Functions inherited from trikNetwork::Connection
 Connection (Protocol connectionProtocol, Heartbeat useHeartbeat)
 Constructor. More...
 
bool isConnected () const
 Returns true if socket is opened or false otherwise. More...
 
bool isValid () const
 Checks if socket is valid or not Attention!!! Hot fix for NTI contest. More...
 
QHostAddress peerAddress () const
 Returns peer address of a connection, if it is open, or empty QHostAddress if connection is not established yet. More...
 
int peerPort () const
 Returns peer port of a connection, if it is open, or -1 if connection is not established yet. More...
 
Q_INVOKABLE void init (qintptr socketDescriptor)
 Creates socket and initializes incoming connection, shall be called when Connection is already in its own thread. More...
 
Q_INVOKABLE void send (const QByteArray &data)
 Sends given byte array to peer. More...
 

Additional Inherited Members

- Signals inherited from trikNetwork::Connection
void disconnected (trikNetwork::Connection *self)
 Emitted after connection becomes closed. More...
 
void connected (trikNetwork::Connection *self)
 Emitted after connection is established. More...
 
- Protected Member Functions inherited from trikNetwork::Connection
void init (const QHostAddress &ip, int port)
 Creates socket and initializes outgoing connection, shall be called when Connection is already in its own thread. More...
 

Detailed Description

Connection class accepts requests for sensors configuration and current sensor values.

Uses a brick passed to it as a constructor parameter to respond to those requests.

Accepted commands: data - sends data from sensors to a client ports - sends current ports configuration to a client

Constructor & Destructor Documentation

Connection::Connection ( trikControl::BrickInterface brick)
explicit

Constructor.

Parameters
brick- a Brick used to respond to clients.
gamepad- gamepad object used to report state of Android gamepad.

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