Go to the documentation of this file.00001 #ifndef __SS_CLIENT_H_
00002 #define __SS_CLIENT_H_
00003
00004 #include <ros/ros.h>
00005
00007 class SerialClient
00008 {
00009 protected:
00010 ros::NodeHandle nh_;
00011 ros::ServiceClient connect_service_;
00012 ros::ServiceClient sendto_service_;
00013 ros::ServiceClient recv_service_;
00014 ros::ServiceClient sendrecv_service_;
00015 ros::Publisher send_topic_;
00016 ros::Publisher close_topic_;
00017 ros::Publisher flush_topic_;
00018
00019 public:
00021
00022 void init(const char *path="/comm");
00023
00025
00029 int connect(float timeout);
00030
00032
00039 int sendto(int socket, const unsigned char *data, size_t length, float timeout);
00040
00042
00051 int recv(int socket, int length, float recv_timeout, float sock_timeout, unsigned char *data, size_t *data_length);
00052
00054
00065 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);
00066
00068
00075 void send(int socket, const unsigned char *data, size_t length, float timeout);
00076
00078
00082 void close(int socket);
00083
00085
00090 void flush(int socket, float timeout);
00091 };
00092
00093 #endif