Public Member Functions | Protected Attributes
SerialClient Class Reference

shared_serial client interface class. More...

#include <client.h>

List of all members.

Public Member Functions

void close (int socket)
 Unlock serial port.
int connect (float timeout)
 Lock serial port.
void flush (int socket, float timeout)
 Flush serial port.
void init (const char *path="/comm")
 Initialize interface.
int recv (int socket, int length, float recv_timeout, float sock_timeout, unsigned char *data, size_t *data_length)
 Receive data from serial port.
void send (int socket, const unsigned char *data, size_t length, float timeout)
 Send data over already locked serial port.
int sendrecv (int socket, const unsigned char *send_data, size_t send_length, size_t recv_length, float recv_timeout, float sock_timeout, unsigned char *recv_data, size_t *recv_data_length)
 Coalesced send and receive.
int sendto (int socket, const unsigned char *data, size_t length, float timeout)
 Send data over serial port.

Protected Attributes

ros::Publisher close_topic_
 Published for close function.
ros::ServiceClient connect_service_
 Service client for connect function.
ros::Publisher flush_topic_
 Publisher for flush function.
ros::NodeHandle nh_
 ROS node handle.
ros::ServiceClient recv_service_
 Service client for recv function.
ros::Publisher send_topic_
 Publisher for send function.
ros::ServiceClient sendrecv_service_
 Service client for sendrecv function.
ros::ServiceClient sendto_service_
 Service client for sendto function.

Detailed Description

shared_serial client interface class.

Definition at line 7 of file client.h.


Member Function Documentation

void SerialClient::close ( int  socket)

Unlock serial port.

Parameters:
socketSocket identifier.
Note:
This function is asynchronous.

Definition at line 111 of file client.cpp.

int SerialClient::connect ( float  timeout)

Lock serial port.

Parameters:
timeoutLock time in [s]
Returns:
Socket identifier.

Definition at line 31 of file client.cpp.

void SerialClient::flush ( int  socket,
float  timeout 
)

Flush serial port.

Parameters:
socketSocket identifier.
timeoutLock time in [s].
Note:
This function is asynchronous.

Definition at line 120 of file client.cpp.

void SerialClient::init ( const char *  path = "/comm")

Initialize interface.

Parameters:
pathPath to server node.

Definition at line 12 of file client.cpp.

int SerialClient::recv ( int  socket,
int  length,
float  recv_timeout,
float  sock_timeout,
unsigned char *  data,
size_t *  data_length 
)

Receive data from serial port.

Parameters:
sockSocket identifier (when 0, the port is locked first).
lengthLength of data to receive.
recv_timeoutTime to wait for data in [s].
sock_timeoutLock time in [s].
dataData buffer, at least length bytes long.
[out]data_lengthNumber of bytes received.
Returns:
Socket identifier.

Definition at line 57 of file client.cpp.

void SerialClient::send ( int  socket,
const unsigned char *  data,
size_t  length,
float  timeout 
)

Send data over already locked serial port.

Parameters:
socketSocket identifier.
dataData to send.
lengthLength of data parameter in bytes.
timeoutLock time in [s].
Note:
This function is asynchronous.

Definition at line 98 of file client.cpp.

int SerialClient::sendrecv ( int  socket,
const unsigned char *  send_data,
size_t  send_length,
size_t  recv_length,
float  recv_timeout,
float  sock_timeout,
unsigned char *  recv_data,
size_t *  recv_data_length 
)

Coalesced send and receive.

Parameters:
socketSocket identifier (when 0, the port is locked first).
send_dataData to send.
send_lengthLength of send_data parameter in bytes.
recv_lengthLength of data to receive.
recv_timeoutTime to wait for data in [s].
sock_timeoutLock time in [s].
recv_dataReceive data buffer, at least recv_length bytes long.
[out]recv_data_lengthNumber of bytes received.
Returns:
Socket identifier.

Definition at line 76 of file client.cpp.

int SerialClient::sendto ( int  socket,
const unsigned char *  data,
size_t  length,
float  timeout 
)

Send data over serial port.

Parameters:
socketSocket identifier (when 0, the port is locked first).
dataData to send.
lengthLength of data parameter.
timeoutLock time in [s].
Returns:
Socket identifier.

Definition at line 41 of file client.cpp.


Member Data Documentation

Published for close function.

Definition at line 16 of file client.h.

Service client for connect function.

Definition at line 11 of file client.h.

Publisher for flush function.

Definition at line 17 of file client.h.

ROS node handle.

Definition at line 10 of file client.h.

Service client for recv function.

Definition at line 13 of file client.h.

Publisher for send function.

Definition at line 15 of file client.h.

Service client for sendrecv function.

Definition at line 14 of file client.h.

Service client for sendto function.

Definition at line 12 of file client.h.


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


shared_serial
Author(s): Wouter Caarls
autogenerated on Fri Aug 28 2015 13:06:29