qb_device_hardware_interface.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_HARDWARE_INTERFACE_H
29 #define QB_DEVICE_HARDWARE_INTERFACE_H
30 
31 // Standard libraries
32 #include <regex>
33 
34 // ROS libraries
35 #include <ros/ros.h>
44 #include <urdf/model.h>
45 
46 // internal libraries
53 
65  public:
77  qbDeviceHW(qb_device_transmission_interface::TransmissionPtr transmission, const std::vector<std::string> &actuators, const std::vector<std::string> &joints);
78 
82  ~qbDeviceHW() override;
83 
87  int getDeviceId() { return device_.id; }
88 
92  std::string getDeviceNamespace() { return device_.name; }
93 
98  virtual std::vector<std::string> getJoints() = 0;
99 
109  bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override;
110 
118  void read(const ros::Time &time, const ros::Duration &period) override;
119 
127  void write(const ros::Time &time, const ros::Duration &period) override;
128 
129  protected:
133  std::map<std::string, ros::ServiceClient> services_;
134  qb_device_msgs::Info device_info_;
143 
149  virtual int activateMotors();
150 
156  virtual int deactivateMotors();
157 
162  virtual std::string getInfo();
163 
178  virtual int getMeasurements(std::vector<double> &positions, std::vector<double> &currents, ros::Time &stamp);
179 
187  virtual int initializeDevice();
188 
198  virtual int setCommands(const std::vector<double> &commands);
199 
200  private:
206  std::vector<std::string> addNamespacePrefix(const std::vector<std::string> &vector);
207 
214 
220  void publish();
221 
229  void resetServicesAndWait(const bool &reinitialize_device = true);
230 
235  void waitForInitialization();
236 
242  void waitForServices();
243 };
244 typedef std::shared_ptr<qbDeviceHW> qbDeviceHWPtr;
245 } // namespace qb_device_hardware_interface
246 
247 #endif // QB_DEVICE_HARDWARE_INTERFACE_H
void resetServicesAndWait(const bool &reinitialize_device=true)
Re-subscribe to all the services advertised by the Communication Handler and wait until all the servi...
qb_device_hardware_interface::qbDeviceHWResources joints_
std::shared_ptr< transmission_interface::Transmission > TransmissionPtr
virtual int getMeasurements(std::vector< double > &positions, std::vector< double > &currents, ros::Time &stamp)
Call the service to retrieve device measurements (both positions and currents) and wait for the respo...
void publish()
Construct a qb_device_msgs::StateStamped message of the whole device state with the data retrieved du...
qb_device_joint_limits_interface::qbDeviceJointLimitsResources joint_limits_
The qbrobotics Device HardWare Resources contains vectors of named joints.
std::shared_ptr< qbDeviceHW > qbDeviceHWPtr
virtual std::string getInfo()
Call the service to retrieve the printable configuration setup of the device and wait for the respons...
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
The init function is called to initialize the RobotHW from a non-realtime thread. ...
The qbrobotics Device HardWare interface extends the hardware_interface::RobotHW by providing all the...
~qbDeviceHW() override
Deactivate motors and stop the async spinner.
qb_device_hardware_interface::qbDeviceResources device_
qb_device_hardware_interface::qbDeviceHWResources actuators_
void write(const ros::Time &time, const ros::Duration &period) override
Enforce joint limits for all registered joint limit interfaces, propagate joint commands to actuators...
The qbrobotics Device Joint Limits Resources is a simple class aimed to group all the joint_limits_in...
virtual int deactivateMotors()
Call the service to deactivate the device motors and wait for the response.
qb_device_transmission_interface::qbDeviceTransmissionResources transmission_
virtual int activateMotors()
Call the service to activate the device motors and wait for the response.
The qbrobotics Device HardWare Interfaces is a simple class aimed to group all the hardware_interface...
void waitForServices()
Wait until all the services advertised by the Communication Handler are active, then reinitialize the...
void initializeServicesAndWait()
Subscribe to all the services advertised by the Communication Handler and wait until all the services...
std::vector< std::string > addNamespacePrefix(const std::vector< std::string > &vector)
Add the namespace prefix stored in the private namespace_ to all the elements of the given vector...
qbDeviceHW(qb_device_transmission_interface::TransmissionPtr transmission, const std::vector< std::string > &actuators, const std::vector< std::string > &joints)
Initialize HW resources and interfaces, and wait until it is initialized from the Communication Handl...
The qbrobotics Device Resources contains just few device information.
virtual int initializeDevice()
Call the service to initialize the device with parameters from the Communication Handler and wait for...
void waitForInitialization()
Wait until the device is initialized.
virtual int setCommands(const std::vector< double > &commands)
Call the service to send reference commands to the device and wait for the response.
std::map< std::string, ros::ServiceClient > services_
qb_device_hardware_interface::qbDeviceHWInterfaces interfaces_
void read(const ros::Time &time, const ros::Duration &period) override
Read actuator state from the hardware, propagate it to joint states and publish the whole device stat...
The qbrobotics Device Transmission Resources is a simple class aimed to group all the transmission_in...
virtual std::vector< std::string > getJoints()=0
This pure virtual method has to be redefined by derived classes to return the controlled joint names ...


qb_device_hardware_interface
Author(s): qbrobotics®
autogenerated on Wed Oct 9 2019 03:45:36