Public Member Functions | Private Member Functions | Private Attributes | List of all members
qb_move_hardware_interface::qbMoveHW Class Reference

The qbrobotics qbmove HardWare interface implements the specific structures to manage the communication with the qbmove device. More...

#include <qb_move_hardware_interface.h>

Inheritance diagram for qb_move_hardware_interface::qbMoveHW:
Inheritance graph
[legend]

Public Member Functions

std::vector< std::string > getJoints () override
 Return the shaft position and stiffness preset joints whether command_with_position_and_preset_ is true; the motors joints otherwise. More...
 
bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
 Call the base method and nothing more. More...
 
 qbMoveHW ()
 Initialize the qb_device_hardware_interface::qbDeviceHW with the specific transmission interface and actuator and joint names. More...
 
void read (const ros::Time &time, const ros::Duration &period) override
 Call the base method and nothing more. More...
 
void write (const ros::Time &time, const ros::Duration &period) override
 Update the shaft joint limits and call the base method. More...
 
 ~qbMoveHW () override
 Do nothing. More...
 
- Public Member Functions inherited from qb_device_hardware_interface::qbDeviceHW
int getDeviceId ()
 
std::string getDeviceNamespace ()
 
 qbDeviceHW (qb_device_transmission_interface::TransmissionPtr transmission, const std::vector< std::string > &actuators, const std::vector< std::string > &joints)
 
 ~qbDeviceHW () override
 
- 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)
 

Private Member Functions

int getMaxStiffness ()
 Parse the maximum value of stiffness of the device from the getInfo string. More...
 
void updateShaftPositionLimits ()
 Update the shaft joint limits since they depend on the fixed motors limits and on the variable stiffness preset. More...
 

Private Attributes

bool command_with_position_and_preset_
 
qb_move_interactive_interface::qbMoveInteractive interactive_interface_
 
double max_motor_limits_
 
double min_motor_limits_
 
double position_ticks_to_radians_
 
double preset_percent_to_radians_
 
bool use_interactive_markers_
 

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
 
- Protected Member Functions inherited from qb_device_hardware_interface::qbDeviceHW
virtual int activateMotors ()
 
virtual int deactivateMotors ()
 
virtual std::string getInfo ()
 
virtual int getMeasurements (std::vector< double > &positions, std::vector< double > &currents, ros::Time &stamp)
 
virtual int initializeDevice ()
 
virtual int setCommands (const std::vector< double > &commands)
 
- Protected Attributes inherited from qb_device_hardware_interface::qbDeviceHW
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_
 

Detailed Description

The qbrobotics qbmove HardWare interface implements the specific structures to manage the communication with the qbmove device.

It exploits the features provided by the base device-independent hardware interface and the specific transmission interface.

See also
qb_device_hardware_interface::qbDeviceHW, qb_move_transmission_interface::qbMoveTransmission

Definition at line 46 of file qb_move_hardware_interface.h.

Constructor & Destructor Documentation

qbMoveHW::qbMoveHW ( )

Initialize the qb_device_hardware_interface::qbDeviceHW with the specific transmission interface and actuator and joint names.

See also
qb_move_transmission_interface::qbMoveTransmission

Definition at line 32 of file qb_move_hardware_interface.cpp.

qbMoveHW::~qbMoveHW ( )
override

Do nothing.

Definition at line 37 of file qb_move_hardware_interface.cpp.

Member Function Documentation

std::vector< std::string > qbMoveHW::getJoints ( )
overridevirtual

Return the shaft position and stiffness preset joints whether command_with_position_and_preset_ is true; the motors joints otherwise.

Returns
The vector of controller joint names.

Implements qb_device_hardware_interface::qbDeviceHW.

Definition at line 41 of file qb_move_hardware_interface.cpp.

int qbMoveHW::getMaxStiffness ( )
private

Parse the maximum value of stiffness of the device from the getInfo string.

Actually it would be better to retrieve it as a firmware parameter, but it is not supported in old firmwares.

Returns
The parsed max value of stiffness.
See also
qb_device_hardware_interface::qbDeviceHW::getInfo()

Definition at line 48 of file qb_move_hardware_interface.cpp.

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

Call the base method and nothing more.

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

Definition at line 59 of file qb_move_hardware_interface.cpp.

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

Call the base method and nothing more.

Parameters
timeThe current time.
periodThe time passed since the last call to this method, i.e. the control period.

Reimplemented from qb_device_hardware_interface::qbDeviceHW.

Definition at line 85 of file qb_move_hardware_interface.cpp.

void qbMoveHW::updateShaftPositionLimits ( )
private

Update the shaft joint limits since they depend on the fixed motors limits and on the variable stiffness preset.

What comes out is that an increase of the variable stiffness decreases the absolute value of the shaft position limit, follwing the formula $JL = \pm\mathopen|JL_{MAX} - S\mathclose|$, where S is the stifness preset (all the values are in ticks).

See also
write()

Definition at line 94 of file qb_move_hardware_interface.cpp.

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

Update the shaft joint limits and call the base method.

The update is necessary since an increase of the variable stiffness decreases the shaft position limits, and vice versa.

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

Reimplemented from qb_device_hardware_interface::qbDeviceHW.

Definition at line 100 of file qb_move_hardware_interface.cpp.

Member Data Documentation

bool qb_move_hardware_interface::qbMoveHW::command_with_position_and_preset_
private

Definition at line 93 of file qb_move_hardware_interface.h.

qb_move_interactive_interface::qbMoveInteractive qb_move_hardware_interface::qbMoveHW::interactive_interface_
private

Definition at line 92 of file qb_move_hardware_interface.h.

double qb_move_hardware_interface::qbMoveHW::max_motor_limits_
private

Definition at line 97 of file qb_move_hardware_interface.h.

double qb_move_hardware_interface::qbMoveHW::min_motor_limits_
private

Definition at line 98 of file qb_move_hardware_interface.h.

double qb_move_hardware_interface::qbMoveHW::position_ticks_to_radians_
private

Definition at line 95 of file qb_move_hardware_interface.h.

double qb_move_hardware_interface::qbMoveHW::preset_percent_to_radians_
private

Definition at line 96 of file qb_move_hardware_interface.h.

bool qb_move_hardware_interface::qbMoveHW::use_interactive_markers_
private

Definition at line 94 of file qb_move_hardware_interface.h.


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


qb_move_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Wed Jun 12 2019 19:18:54