Last change
on this file since 8 was
8,
checked in by wcaarls, 11 years ago
|
Imported shared_serial at revision 990
|
File size:
1.0 KB
|
Rev | Line | |
---|
[8] | 1 | #ifndef __SS_CLIENT_H_ |
---|
| 2 | #define __SS_CLIENT_H_ |
---|
| 3 | |
---|
| 4 | #include <ros/ros.h> |
---|
| 5 | |
---|
| 6 | class SerialClient |
---|
| 7 | { |
---|
| 8 | protected: |
---|
| 9 | ros::NodeHandle nh_; |
---|
| 10 | ros::ServiceClient connect_service_; |
---|
| 11 | ros::ServiceClient sendto_service_; |
---|
| 12 | ros::ServiceClient recv_service_; |
---|
| 13 | ros::ServiceClient sendrecv_service_; |
---|
| 14 | ros::Publisher send_topic_; |
---|
| 15 | ros::Publisher close_topic_; |
---|
| 16 | ros::Publisher flush_topic_; |
---|
| 17 | |
---|
| 18 | public: |
---|
| 19 | void init(const char *path="/comm"); |
---|
| 20 | |
---|
| 21 | int connect(float timeout); |
---|
| 22 | int sendto(int socket, const unsigned char *data, size_t length, float timeout); |
---|
| 23 | int recv(int socket, int length, float recv_timeout, float sock_timeout, unsigned char *data, size_t *data_length); |
---|
| 24 | 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); |
---|
| 25 | void send(int socket, const unsigned char *data, size_t length, float timeout); |
---|
| 26 | void close(int socket); |
---|
| 27 | void flush(int socket, float timeout); |
---|
| 28 | }; |
---|
| 29 | |
---|
| 30 | #endif /* __SS_CLIENT_H_ */ |
---|
Note: See
TracBrowser
for help on using the repository browser.