Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ROSEE::DummyHal Class Reference

Class representing an end-effector. More...

#include <DummyHal.h>

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

Public Types

typedef std::shared_ptr< const DummyHalConstPtr
 
typedef std::shared_ptr< DummyHalPtr
 
- Public Types inherited from ROSEE::EEHal
typedef std::shared_ptr< const EEHalConstPtr
 
typedef std::shared_ptr< EEHalPtr
 

Public Member Functions

 DummyHal (ros::NodeHandle *nh)
 
virtual bool move () override
 
virtual bool sense () override
 
virtual ~DummyHal ()
 
- Public Member Functions inherited from ROSEE::EEHal
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 parseHandInfo ()
 
virtual bool publish_joint_state ()
 
bool publish_pressure ()
 
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 ()
 

Private Member Functions

void hal_js_clbk (const sensor_msgs::JointState::ConstPtr &msg)
 

Private Attributes

ros::Publisher _hal_joint_state_pub
 this will publish to joint_state_publisher More...
 
ros::Subscriber _hal_joint_state_sub
 this will subscribe to joint_state_publisher More...
 

Additional Inherited Members

- Public Attributes inherited from ROSEE::EEHal
bool _pressure_active
 
- Protected Member Functions inherited from ROSEE::EEHal
bool initPressureSensing ()
 
- Protected Attributes inherited from ROSEE::EEHal
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
 

Detailed Description

Class representing an end-effector.

Definition at line 34 of file DummyHal.h.

Member Typedef Documentation

◆ ConstPtr

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

Definition at line 39 of file DummyHal.h.

◆ Ptr

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

Definition at line 38 of file DummyHal.h.

Constructor & Destructor Documentation

◆ DummyHal()

ROSEE::DummyHal::DummyHal ( ros::NodeHandle nh)

Definition at line 20 of file DummyHal.cpp.

◆ ~DummyHal()

virtual ROSEE::DummyHal::~DummyHal ( )
inlinevirtual

Definition at line 42 of file DummyHal.h.

Member Function Documentation

◆ hal_js_clbk()

void ROSEE::DummyHal::hal_js_clbk ( const sensor_msgs::JointState::ConstPtr &  msg)
private

Definition at line 39 of file DummyHal.cpp.

◆ move()

bool ROSEE::DummyHal::move ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 34 of file DummyHal.cpp.

◆ sense()

bool ROSEE::DummyHal::sense ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 29 of file DummyHal.cpp.

Member Data Documentation

◆ _hal_joint_state_pub

ros::Publisher ROSEE::DummyHal::_hal_joint_state_pub
private

this will publish to joint_state_publisher

Definition at line 51 of file DummyHal.h.

◆ _hal_joint_state_sub

ros::Subscriber ROSEE::DummyHal::_hal_joint_state_sub
private

this will subscribe to joint_state_publisher

Definition at line 56 of file DummyHal.h.


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


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:27