shared_serial client interface class. More...
#include <client.h>
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. |
void SerialClient::close | ( | int | socket | ) |
Unlock serial port.
socket | Socket identifier. |
Definition at line 111 of file client.cpp.
int SerialClient::connect | ( | float | timeout | ) |
Lock serial port.
timeout | Lock time in [s] |
Definition at line 31 of file client.cpp.
void SerialClient::flush | ( | int | socket, |
float | timeout | ||
) |
Flush serial port.
socket | Socket identifier. |
timeout | Lock time in [s]. |
Definition at line 120 of file client.cpp.
void SerialClient::init | ( | const char * | path = "/comm" | ) |
Initialize interface.
path | Path 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.
sock | Socket identifier (when 0, the port is locked first). | |
length | Length of data to receive. | |
recv_timeout | Time to wait for data in [s]. | |
sock_timeout | Lock time in [s]. | |
data | Data buffer, at least length bytes long. | |
[out] | data_length | Number of bytes received. |
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.
socket | Socket identifier. |
data | Data to send. |
length | Length of data parameter in bytes. |
timeout | Lock time in [s]. |
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.
socket | Socket identifier (when 0, the port is locked first). | |
send_data | Data to send. | |
send_length | Length of send_data parameter in bytes. | |
recv_length | Length of data to receive. | |
recv_timeout | Time to wait for data in [s]. | |
sock_timeout | Lock time in [s]. | |
recv_data | Receive data buffer, at least recv_length bytes long. | |
[out] | recv_data_length | Number of bytes received. |
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.
socket | Socket identifier (when 0, the port is locked first). |
data | Data to send. |
length | Length of data parameter. |
timeout | Lock time in [s]. |
Definition at line 41 of file client.cpp.
ros::Publisher SerialClient::close_topic_ [protected] |
ros::ServiceClient SerialClient::connect_service_ [protected] |
ros::Publisher SerialClient::flush_topic_ [protected] |
ros::NodeHandle SerialClient::nh_ [protected] |
ros::ServiceClient SerialClient::recv_service_ [protected] |
ros::Publisher SerialClient::send_topic_ [protected] |
ros::ServiceClient SerialClient::sendrecv_service_ [protected] |
ros::ServiceClient SerialClient::sendto_service_ [protected] |