source: trunk/shared_serial/include/shared_serial/client.h @ 12

Last change on this file since 12 was 12, checked in by wcaarls, 12 years ago

Updated shared_serial to revision 1017

File size: 3.4 KB
Line 
1#ifndef __SS_CLIENT_H_
2#define __SS_CLIENT_H_
3
4#include <ros/ros.h>
5
6/// shared_serial client interface class.
7class SerialClient
8{
9  protected:
10    ros::NodeHandle nh_;                  ///< ROS node handle.
11    ros::ServiceClient connect_service_;  ///< Service client for connect function.
12    ros::ServiceClient sendto_service_;   ///< Service client for sendto function.
13    ros::ServiceClient recv_service_;     ///< Service client for recv function.
14    ros::ServiceClient sendrecv_service_; ///< Service client for sendrecv function.
15    ros::Publisher     send_topic_;       ///< Publisher for send function.
16    ros::Publisher     close_topic_;      ///< Published for close function.
17    ros::Publisher     flush_topic_;      ///< Publisher for flush function.
18
19  public:
20    /// Initialize interface.
21    /** \param path Path to server node. */
22    void init(const char *path="/comm");
23
24    /// Lock serial port.
25    /**
26     * \param timeout Lock time in [s]
27     * \returns Socket identifier.
28     */
29    int connect(float timeout);
30   
31    /// Send data over serial port.
32    /**
33     * \param socket Socket identifier (when 0, the port is locked first).
34     * \param data Data to send.
35     * \param length Length of \c data parameter.
36     * \param timeout Lock time in [s].
37     * \returns Socket identifier.
38     */
39    int sendto(int socket, const unsigned char *data, size_t length, float timeout);
40   
41    /// Receive data from serial port.
42    /**
43     * \param sock Socket identifier (when 0, the port is locked first).
44     * \param length Length of data to receive.
45     * \param recv_timeout Time to wait for data in [s].
46     * \param sock_timeout Lock time in [s].
47     * \param data Data buffer, at least \c length bytes long.
48     * \param[out] data_length Number of bytes received.
49     * \returns Socket identifier.
50     */
51    int recv(int socket, int length, float recv_timeout, float sock_timeout, unsigned char *data, size_t *data_length);
52   
53    /// Coalesced send and receive.
54    /**
55     * \param socket Socket identifier (when 0, the port is locked first).
56     * \param send_data Data to send.
57     * \param send_length Length of \c send_data parameter in bytes.
58     * \param recv_length Length of data to receive.
59     * \param recv_timeout Time to wait for data in [s].
60     * \param sock_timeout Lock time in [s].
61     * \param recv_data Receive data buffer, at least \c recv_length bytes long.
62     * \param[out] recv_data_length Number of bytes received.
63     * \returns Socket identifier.
64     */
65    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);
66   
67    /// Send data over already locked serial port.
68    /**
69     * \param socket Socket identifier.
70     * \param data Data to send.
71     * \param length Length of \c data parameter in bytes.
72     * \param timeout Lock time in [s].
73     * \note This function is asynchronous.
74     */
75    void send(int socket, const unsigned char *data, size_t length, float timeout);
76   
77    /// Unlock serial port.
78    /**
79     * \param socket Socket identifier.
80     * \note This function is asynchronous.
81     */
82    void close(int socket);
83   
84    /// Flush serial port.
85    /**
86     * \param socket Socket identifier.
87     * \param timeout Lock time in [s].
88     * \note This function is asynchronous.
89     */
90    void flush(int socket, float timeout);
91};
92
93#endif /* __SS_CLIENT_H_ */
Note: See TracBrowser for help on using the repository browser.