qb_device_communication_handler.h
Go to the documentation of this file.
1 /***
2  * Software License Agreement: BSD 3-Clause License
3  *
4  * Copyright (c) 2016-2018, qbrobotics®
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
8  * following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this list of conditions and the
11  * following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
14  * following disclaimer in the documentation and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote
17  * products derived from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
22  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
24  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE
25  * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef QB_DEVICE_COMMUNICATION_HANDLER_H
29 #define QB_DEVICE_COMMUNICATION_HANDLER_H
30 
31 // Standard libraries
32 #include <mutex>
33 #include <regex>
34 
35 // ROS libraries
36 #include <ros/ros.h>
37 
38 // internal libraries
41 
59  public:
65 
72 
78 
79  protected:
81  std::map<std::string, std::unique_ptr<std::mutex>> serial_protectors_; // only callbacks must lock the serial resources
82  std::map<std::string, comm_settings> file_descriptors_;
83  std::map<int, std::string> connected_devices_;
84 
91  virtual int activate(const int &id, const int &max_repeats);
92 
100  bool activateCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response);
101 
107  virtual int close(const std::string &serial_port);
108 
115  virtual int deactivate(const int &id, const int &max_repeats);
116 
124  bool deactivateCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response);
125 
136  virtual int getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents);
137 
146  virtual int getInfo(const int &id, const int &max_repeats, std::string &info);
147 
155  bool getInfoCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response);
156 
171  virtual int getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents, std::vector<short int> &positions);
172 
180  bool getMeasurementsCallback(qb_device_srvs::GetMeasurementsRequest &request, qb_device_srvs::GetMeasurementsResponse &response);
181 
194  virtual int getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions);
195 
207  virtual int getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions);
208 
219  virtual int getSerialPortsAndDevices(const int &max_repeats);
220 
229  virtual int isActive(const int &id, const int &max_repeats, bool &status);
230 
238  virtual int isConnected(const int &id, const int &max_repeats);
239 
246  virtual bool isInConnectedSet(const int &id);
247 
254  virtual bool isInOpenMap(const std::string &serial_port);
255 
265  virtual bool initializeCallback(qb_device_srvs::InitializeDeviceRequest &request, qb_device_srvs::InitializeDeviceResponse &response);
266 
274  virtual int open(const std::string &serial_port);
275 
286  virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands);
287 
297  virtual int setCommandsAsync(const int &id, std::vector<short int> &commands);
298 
306  bool setCommandsCallback(qb_device_srvs::SetCommandsRequest &request, qb_device_srvs::SetCommandsResponse &response);
307 
316  int setPID(const int &id, const int &max_repeats, std::vector<float> &pid);
317 
326  bool setPIDCallback(qb_device_srvs::SetPIDRequest &request, qb_device_srvs::SetPIDResponse &response);
327 
328  private:
338 
347  virtual int activate(const int &id, const bool &command, const int &max_repeats);
348 
355  inline bool isReliable(int const &failures, int const &max_repeats) { return failures >= 0 && failures <= max_repeats; }
356 };
357 } // namespace qb_device_communication_handler
358 
359 #endif // QB_DEVICE_COMMUNICATION_HANDLER_H
virtual int getMeasurements(const int &id, const int &max_repeats, std::vector< short int > &currents, std::vector< short int > &positions)
Retrieve the motor currents of the given device.
bool getMeasurementsCallback(qb_device_srvs::GetMeasurementsRequest &request, qb_device_srvs::GetMeasurementsResponse &response)
Retrieve the motor positions and currents of the device relative to the node requesting the service...
virtual int getCurrents(const int &id, const int &max_repeats, std::vector< short int > &currents)
Retrieve the motor currents of the given device.
virtual int getInfo(const int &id, const int &max_repeats, std::string &info)
Retrieve the printable configuration setup of the given device.
virtual int getPositions(const int &id, const int &max_repeats, std::vector< short int > &positions)
Retrieve the motor positions of the given device.
virtual int isActive(const int &id, const int &max_repeats, bool &status)
Check whether the motors of the device specified by the given ID are active.
bool setCommandsCallback(qb_device_srvs::SetCommandsRequest &request, qb_device_srvs::SetCommandsResponse &response)
Send the reference command to the motors of the device relative to the node requesting the service...
virtual ~qbDeviceCommunicationHandler()
Close all the still open serial ports.
virtual int getParameters(const int &id, std::vector< int > &limits, std::vector< int > &resolutions)
Retrieve some of the parameters from the given device.
bool getInfoCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response)
Retrieve the printable configuration setup of the device relative to the node requesting the service...
virtual bool initializeCallback(qb_device_srvs::InitializeDeviceRequest &request, qb_device_srvs::InitializeDeviceResponse &response)
Initialize the device node requesting the service to the Communication Handler if the relative physic...
virtual int setCommandsAsync(const int &id, std::vector< short int > &commands)
Send the reference command to the motors of the given device in a non-blocking fashion.
virtual int activate(const int &id, const int &max_repeats)
Activate the motors of the given device.
virtual bool isInOpenMap(const std::string &serial_port)
Check whether the given serial port is managed by the Communication Handler, i.e. ...
bool setPIDCallback(qb_device_srvs::SetPIDRequest &request, qb_device_srvs::SetPIDResponse &response)
Set (temporarily, i.e.
virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector< short int > &commands)
Send the reference command to the motors of the given device and wait for acknowledge.
int setPID(const int &id, const int &max_repeats, std::vector< float > &pid)
Set the position control PID parameters of the given device, temporarily (until power off)...
bool activateCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response)
Activate the motors of the device relative to the node requesting the service.
qbDeviceCommunicationHandler()
Wait until at least one device is connected and then initialize the Communication Handler...
bool isReliable(int const &failures, int const &max_repeats)
Check whether the reading failures are in the given range.
virtual int deactivate(const int &id, const int &max_repeats)
Deactivate the motors of the given device.
virtual int isConnected(const int &id, const int &max_repeats)
Check whether the the device specified by the given ID is connected through the serial port...
The Communication Handler class is aimed to instantiate a ROS node which provides several ROS service...
virtual bool isInConnectedSet(const int &id)
Check whether the physical device specified by the given ID is connected to the Communication Handler...
std::map< std::string, std::unique_ptr< std::mutex > > serial_protectors_
std::shared_ptr< qbDeviceAPI > qbDeviceAPIPtr
virtual int close(const std::string &serial_port)
Close the communication with all the devices connected to the given serial port.
bool deactivateCallback(qb_device_srvs::TriggerRequest &request, qb_device_srvs::TriggerResponse &response)
Deactivate the motors of the device relative to the node requesting the service.
virtual int open(const std::string &serial_port)
Open the serial communication on the given serial port.
virtual int getSerialPortsAndDevices(const int &max_repeats)
Scan for all the serial ports of type /dev/ttyUSB* detected in the system, initialize their mutex pro...


qb_device_driver
Author(s): qbrobotics®
autogenerated on Thu Jun 6 2019 19:46:35