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

Concrete class which communicate directly with ROS topics. More...

#include <XBot2Hal.h>

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

Public Types

typedef std::shared_ptr< const XBot2HalConstPtr
 
typedef std::shared_ptr< XBot2HalPtr
 
- Public Types inherited from ROSEE::EEHal
typedef std::shared_ptr< const EEHalConstPtr
 
typedef std::shared_ptr< EEHalPtr
 

Public Member Functions

virtual bool move () override
 
virtual bool sense () override
 
 XBot2Hal (ros::NodeHandle *nh)
 
virtual ~XBot2Hal ()
 
- 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 Attributes

XBot::JointNameMap _jointPositionActualMap
 
XBot::JointNameMap _jointPositionReferenceMap
 
XBot::RobotInterface::Ptr _robot
 

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

Concrete class which communicate directly with ROS topics.

Definition at line 19 of file XBot2Hal.h.

Member Typedef Documentation

◆ ConstPtr

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

Definition at line 25 of file XBot2Hal.h.

◆ Ptr

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

Definition at line 24 of file XBot2Hal.h.

Constructor & Destructor Documentation

◆ XBot2Hal()

ROSEE::XBot2Hal::XBot2Hal ( ros::NodeHandle nh)

Definition at line 4 of file XBot2Hal.cpp.

◆ ~XBot2Hal()

virtual ROSEE::XBot2Hal::~XBot2Hal ( )
inlinevirtual

Definition at line 28 of file XBot2Hal.h.

Member Function Documentation

◆ move()

bool ROSEE::XBot2Hal::move ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 72 of file XBot2Hal.cpp.

◆ sense()

bool ROSEE::XBot2Hal::sense ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 47 of file XBot2Hal.cpp.

Member Data Documentation

◆ _jointPositionActualMap

XBot::JointNameMap ROSEE::XBot2Hal::_jointPositionActualMap
private

Definition at line 37 of file XBot2Hal.h.

◆ _jointPositionReferenceMap

XBot::JointNameMap ROSEE::XBot2Hal::_jointPositionReferenceMap
private

Definition at line 38 of file XBot2Hal.h.

◆ _robot

XBot::RobotInterface::Ptr ROSEE::XBot2Hal::_robot
private

Definition at line 36 of file XBot2Hal.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