Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
ROSEE::EEHal Class Referenceabstract

Class representing an end-effector. More...

#include <EEHal.h>

Inheritance diagram for ROSEE::EEHal:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< const EEHalConstPtr
 
typedef std::shared_ptr< EEHalPtr
 

Public Member Functions

virtual bool checkCommandPub ()
 
 EEHal (ros::NodeHandle *nh)
 
virtual bool getFingersNames (std::vector< std::string > &fingers_names)
 
Eigen::VectorXd getJointEffort () const
 
Eigen::VectorXd getJointPosition () const
 
Eigen::VectorXd getMotorReference () const
 
virtual bool getMotorsNames (std::vector< std::string > &motors_names)
 
virtual bool getMotorStiffness (Eigen::VectorXd &motors_stiffness)
 
virtual bool getMotorTorqueLimits (Eigen::VectorXd &motors_torque_limits)
 
Eigen::MatrixXd getPressure () const
 
virtual bool getTipJointToTipFrameX (Eigen::VectorXd &tip_joint_to_tip_frame_x)
 
virtual bool getTipJointToTipFrameY (Eigen::VectorXd &tip_joint_to_tip_frame_y)
 
virtual bool getTipsForcesFriction (Eigen::VectorXd &tips_forces_friction)
 
virtual bool getTipsForcesNormal (Eigen::VectorXd &tips_forces_normal)
 
virtual bool getTipsFrictions (Eigen::VectorXd &tips_friction)
 
virtual bool getTipsJacobiansFriction (std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_friction)
 
virtual bool getTipsJacobiansNormal (std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_normal)
 
virtual bool getTransmissionAugmentedMatrices (std::unordered_map< std::string, Eigen::MatrixXd > &transmission_augmented_matrices)
 
virtual bool getTransmissionMatrix (Eigen::MatrixXd &transmission_matrix)
 
virtual bool getTransmissionSquareMatrices (std::unordered_map< std::string, Eigen::MatrixXd > &transmission_square_matrices)
 
virtual bool init_hand_info_response ()
 init the service message with info parsed from yaml file, ie info that will not change according to hand configuration A derived HAL can override this if necessary, since this is called by EEHalExecutor More...
 
virtual bool isHandInfoPresent ()
 
virtual bool move ()=0
 
virtual bool parseHandInfo ()
 
virtual bool publish_joint_state ()
 
bool publish_pressure ()
 
virtual bool sense ()=0
 
virtual bool setHandInfoCallback ()
 Here service is advertise and callback set: if derived class wants to use different callback, they must override this and do : _hand_info_server = _nh->advertiseService(_hand_info_service_name, <custom_callback>);. More...
 
virtual ~EEHal ()
 

Public Attributes

bool _pressure_active
 

Protected Member Functions

bool initPressureSensing ()
 

Protected Attributes

rosee_msg::HandInfo::Response _hand_info_response
 
ros::ServiceServer _hand_info_server
 
std::string _hand_info_service_name
 
ros::Publisher _joint_state_pub
 
sensor_msgs::JointState _js_msg
 
ros::Subscriber _motor_reference_sub
 
sensor_msgs::JointState _mr_msg
 
ros::NodeHandle_nh
 
rosee_msg::MotorPhalangePressure _pressure_msg
 
ros::Publisher _pressure_pub
 
std::vector< std::string > fingers_names
 
std::vector< std::string > motors_names
 
Eigen::VectorXd motors_stiffness
 
Eigen::VectorXd motors_torque_limits
 
Eigen::VectorXd tip_joint_to_tip_frame_x
 
Eigen::VectorXd tip_joint_to_tip_frame_y
 
Eigen::VectorXd tips_frictions
 

Private Member Functions

bool handInfoEEHalCallback (rosee_msg::HandInfo::Request &request, rosee_msg::HandInfo::Response &response)
 
void motor_reference_clbk (const sensor_msgs::JointState::ConstPtr &msg)
 

Private Attributes

bool _hand_info_present
 

Detailed Description

Class representing an end-effector.

Definition at line 54 of file EEHal.h.

Member Typedef Documentation

◆ ConstPtr

typedef std::shared_ptr<const EEHal> ROSEE::EEHal::ConstPtr

Definition at line 59 of file EEHal.h.

◆ Ptr

typedef std::shared_ptr<EEHal> ROSEE::EEHal::Ptr

Definition at line 58 of file EEHal.h.

Constructor & Destructor Documentation

◆ EEHal()

ROSEE::EEHal::EEHal ( ros::NodeHandle nh)

Definition at line 20 of file EEHal.cpp.

◆ ~EEHal()

virtual ROSEE::EEHal::~EEHal ( )
inlinevirtual

Definition at line 62 of file EEHal.h.

Member Function Documentation

◆ checkCommandPub()

bool ROSEE::EEHal::checkCommandPub ( )
virtual

Definition at line 47 of file EEHal.cpp.

◆ getFingersNames()

bool ROSEE::EEHal::getFingersNames ( std::vector< std::string > &  fingers_names)
virtual

Definition at line 69 of file EEHal.cpp.

◆ getJointEffort()

Eigen::VectorXd ROSEE::EEHal::getJointEffort ( ) const

Definition at line 298 of file EEHal.cpp.

◆ getJointPosition()

Eigen::VectorXd ROSEE::EEHal::getJointPosition ( ) const

Definition at line 286 of file EEHal.cpp.

◆ getMotorReference()

Eigen::VectorXd ROSEE::EEHal::getMotorReference ( ) const

Definition at line 274 of file EEHal.cpp.

◆ getMotorsNames()

bool ROSEE::EEHal::getMotorsNames ( std::vector< std::string > &  motors_names)
virtual

Definition at line 81 of file EEHal.cpp.

◆ getMotorStiffness()

bool ROSEE::EEHal::getMotorStiffness ( Eigen::VectorXd &  motors_stiffness)
virtual

Definition at line 94 of file EEHal.cpp.

◆ getMotorTorqueLimits()

bool ROSEE::EEHal::getMotorTorqueLimits ( Eigen::VectorXd &  motors_torque_limits)
virtual

Definition at line 120 of file EEHal.cpp.

◆ getPressure()

Eigen::MatrixXd ROSEE::EEHal::getPressure ( ) const

Definition at line 310 of file EEHal.cpp.

◆ getTipJointToTipFrameX()

bool ROSEE::EEHal::getTipJointToTipFrameX ( Eigen::VectorXd &  tip_joint_to_tip_frame_x)
virtual

Definition at line 133 of file EEHal.cpp.

◆ getTipJointToTipFrameY()

bool ROSEE::EEHal::getTipJointToTipFrameY ( Eigen::VectorXd &  tip_joint_to_tip_frame_y)
virtual

Definition at line 145 of file EEHal.cpp.

◆ getTipsForcesFriction()

virtual bool ROSEE::EEHal::getTipsForcesFriction ( Eigen::VectorXd &  tips_forces_friction)
inlinevirtual

Definition at line 93 of file EEHal.h.

◆ getTipsForcesNormal()

virtual bool ROSEE::EEHal::getTipsForcesNormal ( Eigen::VectorXd &  tips_forces_normal)
inlinevirtual

Definition at line 92 of file EEHal.h.

◆ getTipsFrictions()

bool ROSEE::EEHal::getTipsFrictions ( Eigen::VectorXd &  tips_friction)
virtual

Definition at line 107 of file EEHal.cpp.

◆ getTipsJacobiansFriction()

virtual bool ROSEE::EEHal::getTipsJacobiansFriction ( std::unordered_map< std::string, Eigen::MatrixXd > &  tips_jacobian_friction)
inlinevirtual

Definition at line 88 of file EEHal.h.

◆ getTipsJacobiansNormal()

virtual bool ROSEE::EEHal::getTipsJacobiansNormal ( std::unordered_map< std::string, Eigen::MatrixXd > &  tips_jacobian_normal)
inlinevirtual

Definition at line 87 of file EEHal.h.

◆ getTransmissionAugmentedMatrices()

virtual bool ROSEE::EEHal::getTransmissionAugmentedMatrices ( std::unordered_map< std::string, Eigen::MatrixXd > &  transmission_augmented_matrices)
inlinevirtual

Definition at line 91 of file EEHal.h.

◆ getTransmissionMatrix()

virtual bool ROSEE::EEHal::getTransmissionMatrix ( Eigen::MatrixXd &  transmission_matrix)
inlinevirtual

Definition at line 89 of file EEHal.h.

◆ getTransmissionSquareMatrices()

virtual bool ROSEE::EEHal::getTransmissionSquareMatrices ( std::unordered_map< std::string, Eigen::MatrixXd > &  transmission_square_matrices)
inlinevirtual

Definition at line 90 of file EEHal.h.

◆ handInfoEEHalCallback()

bool ROSEE::EEHal::handInfoEEHalCallback ( rosee_msg::HandInfo::Request &  request,
rosee_msg::HandInfo::Response &  response 
)
private

Definition at line 242 of file EEHal.cpp.

◆ init_hand_info_response()

bool ROSEE::EEHal::init_hand_info_response ( )
virtual

init the service message with info parsed from yaml file, ie info that will not change according to hand configuration A derived HAL can override this if necessary, since this is called by EEHalExecutor

Definition at line 217 of file EEHal.cpp.

◆ initPressureSensing()

bool ROSEE::EEHal::initPressureSensing ( )
protected

Definition at line 253 of file EEHal.cpp.

◆ isHandInfoPresent()

bool ROSEE::EEHal::isHandInfoPresent ( )
virtual

Definition at line 52 of file EEHal.cpp.

◆ motor_reference_clbk()

void ROSEE::EEHal::motor_reference_clbk ( const sensor_msgs::JointState::ConstPtr &  msg)
private

Definition at line 54 of file EEHal.cpp.

◆ move()

virtual bool ROSEE::EEHal::move ( )
pure virtual

Implemented in ROSEE::DummyHal, and ROSEE::XBot2Hal.

◆ parseHandInfo()

bool ROSEE::EEHal::parseHandInfo ( )
virtual

Definition at line 157 of file EEHal.cpp.

◆ publish_joint_state()

bool ROSEE::EEHal::publish_joint_state ( )
virtual

Definition at line 60 of file EEHal.cpp.

◆ publish_pressure()

bool ROSEE::EEHal::publish_pressure ( )

Definition at line 265 of file EEHal.cpp.

◆ sense()

virtual bool ROSEE::EEHal::sense ( )
pure virtual

Implemented in ROSEE::DummyHal, and ROSEE::XBot2Hal.

◆ setHandInfoCallback()

bool ROSEE::EEHal::setHandInfoCallback ( )
virtual

Here service is advertise and callback set: if derived class wants to use different callback, they must override this and do : _hand_info_server = _nh->advertiseService(_hand_info_service_name, <custom_callback>);.

Definition at line 235 of file EEHal.cpp.

Member Data Documentation

◆ _hand_info_present

bool ROSEE::EEHal::_hand_info_present
private

Definition at line 157 of file EEHal.h.

◆ _hand_info_response

rosee_msg::HandInfo::Response ROSEE::EEHal::_hand_info_response
protected

Definition at line 151 of file EEHal.h.

◆ _hand_info_server

ros::ServiceServer ROSEE::EEHal::_hand_info_server
protected

Definition at line 150 of file EEHal.h.

◆ _hand_info_service_name

std::string ROSEE::EEHal::_hand_info_service_name
protected

Definition at line 152 of file EEHal.h.

◆ _joint_state_pub

ros::Publisher ROSEE::EEHal::_joint_state_pub
protected

Definition at line 137 of file EEHal.h.

◆ _js_msg

sensor_msgs::JointState ROSEE::EEHal::_js_msg
protected

The states that must be filled in the sense(), reading info from real/simulated robot TODO put private and create a set (no get) ?

Definition at line 136 of file EEHal.h.

◆ _motor_reference_sub

ros::Subscriber ROSEE::EEHal::_motor_reference_sub
protected

Definition at line 130 of file EEHal.h.

◆ _mr_msg

sensor_msgs::JointState ROSEE::EEHal::_mr_msg
protected

The references that must be read in the move() to send to the real/simulated robot TODO put private and create a get ? (no set)

Definition at line 129 of file EEHal.h.

◆ _nh

ros::NodeHandle* ROSEE::EEHal::_nh
protected

Definition at line 123 of file EEHal.h.

◆ _pressure_active

bool ROSEE::EEHal::_pressure_active

Definition at line 112 of file EEHal.h.

◆ _pressure_msg

rosee_msg::MotorPhalangePressure ROSEE::EEHal::_pressure_msg
protected

Definition at line 141 of file EEHal.h.

◆ _pressure_pub

ros::Publisher ROSEE::EEHal::_pressure_pub
protected

Definition at line 142 of file EEHal.h.

◆ fingers_names

std::vector<std::string> ROSEE::EEHal::fingers_names
protected

Definition at line 146 of file EEHal.h.

◆ motors_names

std::vector<std::string> ROSEE::EEHal::motors_names
protected

Definition at line 146 of file EEHal.h.

◆ motors_stiffness

Eigen::VectorXd ROSEE::EEHal::motors_stiffness
protected

Definition at line 147 of file EEHal.h.

◆ motors_torque_limits

Eigen::VectorXd ROSEE::EEHal::motors_torque_limits
protected

Definition at line 147 of file EEHal.h.

◆ tip_joint_to_tip_frame_x

Eigen::VectorXd ROSEE::EEHal::tip_joint_to_tip_frame_x
protected

Definition at line 147 of file EEHal.h.

◆ tip_joint_to_tip_frame_y

Eigen::VectorXd ROSEE::EEHal::tip_joint_to_tip_frame_y
protected

Definition at line 147 of file EEHal.h.

◆ tips_frictions

Eigen::VectorXd ROSEE::EEHal::tips_frictions
protected

Definition at line 147 of file EEHal.h.


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


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Tue Apr 5 2022 02:57:53