Public Member Functions | Private Attributes | List of all members
qb_device_joint_limits_interface::qbDeviceJointLimitsResources Class Reference

The qbrobotics Device Joint Limits Resources is a simple class aimed to group all the joint_limits_interface:: related structures in a unique place. More...

#include <qb_device_joint_limits_resources.h>

Public Member Functions

void initialize (ros::NodeHandle &robot_hw_nh, qb_device_hardware_interface::qbDeviceHWResources &joints, const urdf::Model &urdf_model, hardware_interface::PositionJointInterface &joint_position)
 Retrieve the joint limits for each given joint. More...
 
 qbDeviceJointLimitsResources ()
 Do nothing. More...
 
virtual ~qbDeviceJointLimitsResources ()
 Do nothing. More...
 
Real-Time Safe Functions
void enforceLimits (const ros::Duration &period)
 Enforce limits for all managed interfaces. More...
 

Private Attributes

bool has_limits_
 
bool has_soft_limits_
 
PositionJointSaturationInterface joint_position_saturation_
 

Detailed Description

The qbrobotics Device Joint Limits Resources is a simple class aimed to group all the joint_limits_interface:: related structures in a unique place.

For the sake of uniformity, both qbhand and qbmove devices exploit the same joint position saturation interface with dynamical management of the joint limits, specifically designed for the qbmove shaft limits which vary in relation to the variable stiffness preset. The qbhand has fixed joint limits, though.

See also
PositionJointSaturationHandle
Todo:
Add soft limits support.

Definition at line 41 of file qb_device_joint_limits_resources.h.

Constructor & Destructor Documentation

qb_device_joint_limits_interface::qbDeviceJointLimitsResources::qbDeviceJointLimitsResources ( )
inline

Do nothing.

See also
initialize()

Definition at line 47 of file qb_device_joint_limits_resources.h.

virtual qb_device_joint_limits_interface::qbDeviceJointLimitsResources::~qbDeviceJointLimitsResources ( )
inlinevirtual

Do nothing.

Definition at line 52 of file qb_device_joint_limits_resources.h.

Member Function Documentation

void qb_device_joint_limits_interface::qbDeviceJointLimitsResources::enforceLimits ( const ros::Duration period)
inline

Enforce limits for all managed interfaces.

Parameters
periodThe control period.

Definition at line 59 of file qb_device_joint_limits_resources.h.

void qb_device_joint_limits_interface::qbDeviceJointLimitsResources::initialize ( ros::NodeHandle robot_hw_nh,
qb_device_hardware_interface::qbDeviceHWResources joints,
const urdf::Model urdf_model,
hardware_interface::PositionJointInterface joint_position 
)
inline

Retrieve the joint limits for each given joint.

At first they are taken from the robot_description (URDF model), but these values are overridden by the one specified in the Parameter Server, if found.

Parameters
jointsThe device HW joints Resource.
urdf_modelThe URDF model structure initialized with the robot_description.
joint_positionThe joint position HW interface, needed to retrieve joint handles.
Todo:
Add soft limits support.

Definition at line 78 of file qb_device_joint_limits_resources.h.

Member Data Documentation

bool qb_device_joint_limits_interface::qbDeviceJointLimitsResources::has_limits_
private

Definition at line 105 of file qb_device_joint_limits_resources.h.

bool qb_device_joint_limits_interface::qbDeviceJointLimitsResources::has_soft_limits_
private

Definition at line 106 of file qb_device_joint_limits_resources.h.

PositionJointSaturationInterface qb_device_joint_limits_interface::qbDeviceJointLimitsResources::joint_position_saturation_
private

Definition at line 110 of file qb_device_joint_limits_resources.h.


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


qb_device_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Thu Jun 6 2019 19:46:29