Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
qb_device_hardware_interface::qbDeviceHW Class Referenceabstract

The qbrobotics Device HardWare interface extends the hardware_interface::RobotHW by providing all the common structures to manage the communication with both the qbhand and qbmove devices. More...

#include <qb_device_hardware_interface.h>

Inheritance diagram for qb_device_hardware_interface::qbDeviceHW:
Inheritance graph
[legend]

Public Member Functions

int getDeviceId ()
 
std::string getDeviceNamespace ()
 
virtual std::vector< std::string > getJoints ()=0
 This pure virtual method has to be redefined by derived classes to return the controlled joint names vector. More...
 
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. More...
 
 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 Handler. More...
 
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 state to a namespaced "~state" topic (each instance of qbDeviceHW should publish on its own topic). More...
 
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, and send actuator commands to the hardware. More...
 
 ~qbDeviceHW () override
 Deactivate motors and stop the async spinner. More...
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
 RobotHW ()
 
virtual ~RobotHW ()
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Protected Member Functions

virtual int activateMotors ()
 Call the service to activate the device motors and wait for the response. More...
 
virtual int deactivateMotors ()
 Call the service to deactivate the device motors and wait for the response. More...
 
virtual std::string getInfo ()
 Call the service to retrieve the printable configuration setup of the device and wait for the response. More...
 
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 response. More...
 
virtual int initializeDevice ()
 Call the service to initialize the device with parameters from the Communication Handler and wait for the response. More...
 
virtual int setCommands (const std::vector< double > &commands)
 Call the service to send reference commands to the device and wait for the response. More...
 

Protected Attributes

qb_device_hardware_interface::qbDeviceHWResources actuators_
 
qb_device_hardware_interface::qbDeviceResources device_
 
qb_device_msgs::Info device_info_
 
qb_device_hardware_interface::qbDeviceHWInterfaces interfaces_
 
qb_device_joint_limits_interface::qbDeviceJointLimitsResources joint_limits_
 
qb_device_hardware_interface::qbDeviceHWResources joints_
 
ros::NodeHandle node_handle_
 
std::map< std::string, ros::ServiceClientservices_
 
ros::AsyncSpinner spinner_
 
ros::Publisher state_publisher_
 
qb_device_transmission_interface::qbDeviceTransmissionResources transmission_
 
urdf::Model urdf_model_
 
bool use_simulator_mode_
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Private Member Functions

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. More...
 
void initializeServicesAndWait ()
 Subscribe to all the services advertised by the Communication Handler and wait until all the services are properly advertised. More...
 
void publish ()
 Construct a qb_device_msgs::StateStamped message of the whole device state with the data retrieved during the read() and publish it to a namespaced "~state" topic. More...
 
void resetServicesAndWait (const bool &reinitialize_device=true)
 Re-subscribe to all the services advertised by the Communication Handler and wait until all the services are properly advertised. More...
 
void waitForInitialization ()
 Wait until the device is initialized. More...
 
void waitForServices ()
 Wait until all the services advertised by the Communication Handler are active, then reinitialize the device to avoid disconnection problems. More...
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 

Detailed Description

The qbrobotics Device HardWare interface extends the hardware_interface::RobotHW by providing all the common structures to manage the communication with both the qbhand and qbmove devices.

The few differences among them are implemented in the two device-specific derived classes, qbHandHW and qbMoveHW. In detail, this class initialize all the ROS service clients needed to talk to the Communication Handler which is the intermediary for the serial communication with the physical devices. The core part is given by the two overridden function of the hardware_interface::RobotHW base class, i.e. read() and write(), which are meant to be used in the control loop.

See also
qb_hand_hardware_interface::qbHandHW, qb_move_hardware_interface::qbMoveHW

Definition at line 64 of file qb_device_hardware_interface.h.

Constructor & Destructor Documentation

qbDeviceHW::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 Handler.

If the Communication Handler is not running, wait forever. The three given parameters are strictly device-dependent, i.e. the qbhand specific transmission differs from the qbmove one, and the actuator and joint names depend not only on the device type, but also on the whole robot_description extracted from the URDF model. For example each qbmove of a given chain has its own namespace to avoid name clashes.

Parameters
transmissionThe shared pointer to the current transmission derived from transmission_interface::Transmission.
actuatorsThe actuator names in the robot_description.
jointsThe joint names in the robot_description.
See also
initializeInterfaces(), initializeResources(), waitForInitialization(), waitForServices()

Definition at line 32 of file qb_device_hardware_interface.cpp.

qbDeviceHW::~qbDeviceHW ( )
override

Deactivate motors and stop the async spinner.

Definition at line 41 of file qb_device_hardware_interface.cpp.

Member Function Documentation

int qbDeviceHW::activateMotors ( )
protectedvirtual

Call the service to activate the device motors and wait for the response.

Returns
0 on success.
See also
deactivateMotors()

Definition at line 46 of file qb_device_hardware_interface.cpp.

std::vector< std::string > qbDeviceHW::addNamespacePrefix ( const std::vector< std::string > &  vector)
private

Add the namespace prefix stored in the private namespace_ to all the elements of the given vector.

Parameters
vectorAny vector of strings.
Returns
The namespaced vector.

Definition at line 64 of file qb_device_hardware_interface.cpp.

int qbDeviceHW::deactivateMotors ( )
protectedvirtual

Call the service to deactivate the device motors and wait for the response.

Returns
0 on success.
See also
activateMotors()

Definition at line 75 of file qb_device_hardware_interface.cpp.

int qb_device_hardware_interface::qbDeviceHW::getDeviceId ( )
inline
Returns
The device ID, in range [1, 128].

Definition at line 87 of file qb_device_hardware_interface.h.

std::string qb_device_hardware_interface::qbDeviceHW::getDeviceNamespace ( )
inline
Returns
The device namespace used to avoid name clashes among same-type devices.

Definition at line 92 of file qb_device_hardware_interface.h.

std::string qbDeviceHW::getInfo ( )
protectedvirtual

Call the service to retrieve the printable configuration setup of the device and wait for the response.

Returns
The configuration setup formatted as a plain text string (empty string on error).

Definition at line 93 of file qb_device_hardware_interface.cpp.

virtual std::vector<std::string> qb_device_hardware_interface::qbDeviceHW::getJoints ( )
pure virtual

This pure virtual method has to be redefined by derived classes to return the controlled joint names vector.

Returns
The vector of controller joint names.
int qbDeviceHW::getMeasurements ( std::vector< double > &  positions,
std::vector< double > &  currents,
ros::Time stamp 
)
protectedvirtual

Call the service to retrieve device measurements (both positions and currents) and wait for the response.

When data is received, correct the positions direction with the motor_axis_direction.

Parameters
[out]positionsThe device position vector, expressed in ticks: if the device is a qbhand only the first element is filled while the others remain always 0; in the case of a qbmove all the elements contain relevant data, i.e. the positions respectively of motor_1, motor_2 and motor_shaft (which is not directly actuated).
[out]currentsThe two-element device motor current vector, expressed in mA: if the device is a qbhand only the first element is filled while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the currents respectively of motor_1 and motor_2.
[out]stampThe time stamp of the retrieved measurements (it is set by the process which does the read).
Returns
0 on success.
See also
setCommands()

Definition at line 110 of file qb_device_hardware_interface.cpp.

bool qbDeviceHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
overridevirtual

The init function is called to initialize the RobotHW from a non-realtime thread.

In particular it build the HW resources, retrieve the robot_description from the Parameter Server, and initialize the hardware_interface, the joint_limit_interface, and the transmission_interface. If everything goes as expected it also initialize the current device with the parameters retrieve from the Communication Handler.

Parameters
root_nhA NodeHandle in the root of the caller namespace.
robot_hw_nhA NodeHandle in the namespace from which the RobotHW should read its configuration.
Returns
true on success.

Reimplemented from hardware_interface::RobotHW.

Definition at line 139 of file qb_device_hardware_interface.cpp.

int qbDeviceHW::initializeDevice ( )
protectedvirtual

Call the service to initialize the device with parameters from the Communication Handler and wait for the response.

If the initializaation succeed, store the device parameters received, e.g. position_limits. It can additionally activate motors during the initialization process, if specified in the Parameter Server.

Returns
0 on success.
See also
waitForInitialization()

Definition at line 171 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::initializeServicesAndWait ( )
private

Subscribe to all the services advertised by the Communication Handler and wait until all the services are properly advertised.

See also
resetServicesAndWait(), waitForServices()

Definition at line 213 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::publish ( )
private

Construct a qb_device_msgs::StateStamped message of the whole device state with the data retrieved during the read() and publish it to a namespaced "~state" topic.

See also
read()

Definition at line 223 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::read ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Read actuator state from the hardware, propagate it to joint states and publish the whole device state to a namespaced "~state" topic (each instance of qbDeviceHW should publish on its own topic).

Parameters
timeThe current time.
periodThe time passed since the last call to this method, i.e. the control period.
See also
getMeasurements(), publish()

Reimplemented from hardware_interface::RobotHW.

Definition at line 255 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::resetServicesAndWait ( const bool &  reinitialize_device = true)
private

Re-subscribe to all the services advertised by the Communication Handler and wait until all the services are properly advertised.

Then re-initialize the device parameters (it is assumed that the this method can be called only if the device was previously initialized), unless otherwise specified.

Parameters
reinitialize_deviceIf true, i.e. by default, reinitialize the device.
See also
initializeServicesAndWait(), waitForInitialization(), waitForServices()

Definition at line 280 of file qb_device_hardware_interface.cpp.

int qbDeviceHW::setCommands ( const std::vector< double > &  commands)
protectedvirtual

Call the service to send reference commands to the device and wait for the response.

Before sending the references, correct their direction with the motor_axis_direction.

Parameters
commandsThe reference command vector, expressed in ticks: if the device is a qbhand only the first element is meaningful while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the commands respectively of motor_1 and motor_2.
Returns
0 on success.
See also
getMeasurements()

Definition at line 289 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::waitForInitialization ( )
private

Wait until the device is initialized.

See also
initializeDevice()

Definition at line 313 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::waitForServices ( )
private

Wait until all the services advertised by the Communication Handler are active, then reinitialize the device to avoid disconnection problems.

See also
initializeServicesAndWait(), resetServicesAndWait()

Definition at line 319 of file qb_device_hardware_interface.cpp.

void qbDeviceHW::write ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Enforce joint limits for all registered joint limit interfaces, propagate joint commands to actuators, and send actuator commands to the hardware.

Parameters
timeThe current time.
periodThe time passed since the last call to this method, i.e. the control period.
See also
qb_device_joint_limits_interface::qbDeviceJointLimitsResources::enforceLimits(), setCommands()

Reimplemented from hardware_interface::RobotHW.

Definition at line 326 of file qb_device_hardware_interface.cpp.

Member Data Documentation

qb_device_hardware_interface::qbDeviceHWResources qb_device_hardware_interface::qbDeviceHW::actuators_
protected

Definition at line 136 of file qb_device_hardware_interface.h.

qb_device_hardware_interface::qbDeviceResources qb_device_hardware_interface::qbDeviceHW::device_
protected

Definition at line 135 of file qb_device_hardware_interface.h.

qb_device_msgs::Info qb_device_hardware_interface::qbDeviceHW::device_info_
protected

Definition at line 134 of file qb_device_hardware_interface.h.

qb_device_hardware_interface::qbDeviceHWInterfaces qb_device_hardware_interface::qbDeviceHW::interfaces_
protected

Definition at line 138 of file qb_device_hardware_interface.h.

qb_device_joint_limits_interface::qbDeviceJointLimitsResources qb_device_hardware_interface::qbDeviceHW::joint_limits_
protected

Definition at line 139 of file qb_device_hardware_interface.h.

qb_device_hardware_interface::qbDeviceHWResources qb_device_hardware_interface::qbDeviceHW::joints_
protected

Definition at line 137 of file qb_device_hardware_interface.h.

ros::NodeHandle qb_device_hardware_interface::qbDeviceHW::node_handle_
protected

Definition at line 131 of file qb_device_hardware_interface.h.

std::map<std::string, ros::ServiceClient> qb_device_hardware_interface::qbDeviceHW::services_
protected

Definition at line 133 of file qb_device_hardware_interface.h.

ros::AsyncSpinner qb_device_hardware_interface::qbDeviceHW::spinner_
protected

Definition at line 130 of file qb_device_hardware_interface.h.

ros::Publisher qb_device_hardware_interface::qbDeviceHW::state_publisher_
protected

Definition at line 132 of file qb_device_hardware_interface.h.

qb_device_transmission_interface::qbDeviceTransmissionResources qb_device_hardware_interface::qbDeviceHW::transmission_
protected

Definition at line 140 of file qb_device_hardware_interface.h.

urdf::Model qb_device_hardware_interface::qbDeviceHW::urdf_model_
protected

Definition at line 141 of file qb_device_hardware_interface.h.

bool qb_device_hardware_interface::qbDeviceHW::use_simulator_mode_
protected

Definition at line 142 of file qb_device_hardware_interface.h.


The documentation for this class was generated from the following files:


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