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

Class representing and End-Effector. More...

#include <EEInterface.h>

Public Types

typedef std::shared_ptr< const EEInterfaceConstPtr
 
typedef std::shared_ptr< EEInterfacePtr
 

Public Member Functions

 EEInterface (const ROSEE::Parser &p)
 
const std::vector< std::string > & getActuatedJoints ()
 getter for the actuated joints of the end-effector More...
 
bool getActuatedJointsInFinger (std::string finger_name, std::vector< std::string > &actuated_joints)
 getter for the actuated joints of a finger More...
 
int getActuatedJointsNum ()
 getter for the number of actuated joints in the end-effector More...
 
int getActuatedJointsNumInFinger (std::string finger_name)
 getter for the number of actuated joints in the requested finger More...
 
const std::vector< std::string > & getFingers ()
 getter for the fingers name in the current End-Effector More...
 
int getFingersNumber ()
 getter for the number of fingers in the End-Effector More...
 
bool getInternalIdForJoint (std::string joint_name, int &internal_id)
 getter for the internal id of a certain joint More...
 
bool getInternalIdsForFinger (std::string finger_name, std::vector< int > &internal_ids)
 getter for the internal ids (position in the EEInterface vectors) of joints in a certain finger More...
 
Eigen::VectorXd getLowerPositionLimits ()
 getter for the lower position limits of EE joints as specified in the URDF More...
 
std::string getName ()
 getter for the EE name More...
 
Eigen::VectorXd getUpperPositionLimits ()
 getter for the upper position limits of EE joints as specified in the URDF More...
 
bool isFinger (std::string finger_name)
 check is the requested finger exists More...
 
virtual ~EEInterface ()
 

Private Attributes

std::vector< std::string > _actuated_joints
 
std::map< std::string, std::vector< std::string > > _ee_description
 
std::string _ee_name
 
std::map< std::string, std::vector< int > > _finger_joints_internal_id_map
 
std::vector< std::string > _fingers_names
 
std::map< std::string, int > _joints_internal_id_map
 
int _joints_num = 0
 
Eigen::VectorXd _lower_limits
 
Eigen::VectorXd _upper_limits
 
std::map< std::string, urdf::JointConstSharedPtr > _urdf_joint_map
 

Detailed Description

Class representing and End-Effector.

Definition at line 36 of file EEInterface.h.

Member Typedef Documentation

◆ ConstPtr

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

Definition at line 41 of file EEInterface.h.

◆ Ptr

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

Definition at line 40 of file EEInterface.h.

Constructor & Destructor Documentation

◆ EEInterface()

ROSEE::EEInterface::EEInterface ( const ROSEE::Parser p)

Definition at line 20 of file EEInterface.cpp.

◆ ~EEInterface()

ROSEE::EEInterface::~EEInterface ( )
virtual

Definition at line 160 of file EEInterface.cpp.

Member Function Documentation

◆ getActuatedJoints()

const std::vector< std::string > & ROSEE::EEInterface::getActuatedJoints ( )

getter for the actuated joints of the end-effector

Returns
const std::vector< std::string >& the actuated joint in the End-Effector as a vector of String

Definition at line 122 of file EEInterface.cpp.

◆ getActuatedJointsInFinger()

bool ROSEE::EEInterface::getActuatedJointsInFinger ( std::string  finger_name,
std::vector< std::string > &  actuated_joints 
)

getter for the actuated joints of a finger

Parameters
finger_namethe name of the finger where to retrieve actuated joints
actuated_joints[out] will be filled with the actuated joints of the finger
Returns
bool true if the requested finger exists, false otherwise

Definition at line 128 of file EEInterface.cpp.

◆ getActuatedJointsNum()

int ROSEE::EEInterface::getActuatedJointsNum ( )

getter for the number of actuated joints in the end-effector

Returns
int the number of actuated joints in the end effector

Definition at line 139 of file EEInterface.cpp.

◆ getActuatedJointsNumInFinger()

int ROSEE::EEInterface::getActuatedJointsNumInFinger ( std::string  finger_name)

getter for the number of actuated joints in the requested finger

Parameters
finger_namethe name of the finger where to retrieve the number of actuated joints
Returns
int the number of actuated joints in finger_name, or -1 if the finger does not exists

Definition at line 144 of file EEInterface.cpp.

◆ getFingers()

const std::vector< std::string > & ROSEE::EEInterface::getFingers ( )

getter for the fingers name in the current End-Effector

Returns
std::vector<std::string>& existing finger names in the End-Effector

Definition at line 110 of file EEInterface.cpp.

◆ getFingersNumber()

int ROSEE::EEInterface::getFingersNumber ( )

getter for the number of fingers in the End-Effector

Returns
int the number of fingers in the End-Effector

Definition at line 154 of file EEInterface.cpp.

◆ getInternalIdForJoint()

bool ROSEE::EEInterface::getInternalIdForJoint ( std::string  joint_name,
int &  internal_id 
)

getter for the internal id of a certain joint

Parameters
joint_namethe name of the requested joint
internal_idthe internal id of the requested joint
Returns
bool true if the joint exists, false otherwise

Definition at line 85 of file EEInterface.cpp.

◆ getInternalIdsForFinger()

bool ROSEE::EEInterface::getInternalIdsForFinger ( std::string  finger_name,
std::vector< int > &  internal_ids 
)

getter for the internal ids (position in the EEInterface vectors) of joints in a certain finger

Parameters
finger_namethe name of the requested finger
internal_idsthe internal ids of the joints in the requested finger
Returns
bool true if the finger exists, false otherwise

Definition at line 98 of file EEInterface.cpp.

◆ getLowerPositionLimits()

Eigen::VectorXd ROSEE::EEInterface::getLowerPositionLimits ( )

getter for the lower position limits of EE joints as specified in the URDF

Returns
Eigen::VectorXd the lower position limits of EE joints as specified in the URDF

Definition at line 75 of file EEInterface.cpp.

◆ getName()

std::string ROSEE::EEInterface::getName ( )

getter for the EE name

Returns
std::string the EE name parsed from the given config files of the EE

Definition at line 69 of file EEInterface.cpp.

◆ getUpperPositionLimits()

Eigen::VectorXd ROSEE::EEInterface::getUpperPositionLimits ( )

getter for the upper position limits of EE joints as specified in the URDF

Returns
Eigen::VectorXd the upper position limits of EE joints as specified in the URDF

Definition at line 80 of file EEInterface.cpp.

◆ isFinger()

bool ROSEE::EEInterface::isFinger ( std::string  finger_name)

check is the requested finger exists

Parameters
finger_namename of the finger to check
Returns
true if the finger exists, false otherwise

Definition at line 115 of file EEInterface.cpp.

Member Data Documentation

◆ _actuated_joints

std::vector<std::string> ROSEE::EEInterface::_actuated_joints
private

Definition at line 149 of file EEInterface.h.

◆ _ee_description

std::map<std::string, std::vector<std::string> > ROSEE::EEInterface::_ee_description
private

Definition at line 142 of file EEInterface.h.

◆ _ee_name

std::string ROSEE::EEInterface::_ee_name
private

Definition at line 153 of file EEInterface.h.

◆ _finger_joints_internal_id_map

std::map<std::string, std::vector<int> > ROSEE::EEInterface::_finger_joints_internal_id_map
private

Definition at line 145 of file EEInterface.h.

◆ _fingers_names

std::vector<std::string> ROSEE::EEInterface::_fingers_names
private

Definition at line 149 of file EEInterface.h.

◆ _joints_internal_id_map

std::map<std::string, int> ROSEE::EEInterface::_joints_internal_id_map
private

Definition at line 147 of file EEInterface.h.

◆ _joints_num

int ROSEE::EEInterface::_joints_num = 0
private

Definition at line 155 of file EEInterface.h.

◆ _lower_limits

Eigen::VectorXd ROSEE::EEInterface::_lower_limits
private

Definition at line 151 of file EEInterface.h.

◆ _upper_limits

Eigen::VectorXd ROSEE::EEInterface::_upper_limits
private

Definition at line 151 of file EEInterface.h.

◆ _urdf_joint_map

std::map<std::string, urdf::JointConstSharedPtr> ROSEE::EEInterface::_urdf_joint_map
private

Definition at line 143 of file EEInterface.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