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

Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementation and the EEInterface. More...

#include <Parser.h>

Public Types

typedef std::shared_ptr< const ParserConstPtr
 
typedef std::shared_ptr< ParserPtr
 

Public Member Functions

std::string getActionPath () const
 get the path where emit and parse grasping actions More...
 
int getActuatedJointsNumber () const
 getter for the total number of actuated joints in the configuration files More...
 
std::string getEndEffectorName () const
 getter for the configure End-Effector name More...
 
std::map< std::string, std::vector< std::string > > getFingerJointMap () const
 getter for a description of the End-Effector as a map of finger name, finger joint names. There exists another version to get the map as reference: getFingerJointMapAsReference More...
 
void getFingerJointMap (std::map< std::string, std::vector< std::string >> &finger_joint_map) const
 getter for the map between the finger kinematic chains and the related actuated joints, reference version of getFingerJointMap More...
 
std::map< std::string, std::string > getJointFingerMap () const
 getter for a description of the End-Effector as a map of joint name, finger name More...
 
void getJointFingerMap (std::map< std::string, std::string > &joint_finger_map) const
 getter for a description of the End-Effector as a map of joint name, finger name More...
 
std::string getRoseeConfigPath () const
 get the filename (with path) of the yaml config file. Useful get to print infos about file parsed outside this class More...
 
std::string getSrdfString () const
 get the whole srdf file parsed as a string More...
 
std::map< std::string, urdf::JointConstSharedPtr > getUrdfJointMap () const
 getter for the URDF information of the joints of the End-Effector More...
 
std::string getUrdfString () const
 get the whole urdf file parsed as a string More...
 
bool init ()
 Initialization function using the ROS param ROSEEConfigPath. More...
 
bool init (const std::string &urdf_path, const std::string &srdf_path, const std::string &action_path)
 Initialization function using the path_to_cfg parameter for the path. More...
 
 Parser (const ros::NodeHandle &nh)
 
void printEndEffectorFingerJointsMap () const
 Utility to print the mapping between the End Effector finger chains and the related actuated joints. More...
 
virtual ~Parser ()
 

Private Member Functions

void addNotInFingerJoints ()
 
bool configure ()
 configure the ROSEE parser based on the configration files requested More...
 
bool getJointsInFinger (std::string base_link, std::string tip_link, std::string finger_name)
 fill a data structure related with the revolute/prismatic joints included in between base_link and tip_link in the requested URDF More...
 
bool parseSRDF ()
 Function responsible to parse the SRDF data. More...
 
bool parseURDF ()
 Function responsible to get the file needed to fill the internal data structure of the Parser with data coming from the ros_ee configuration file requested by the user. More...
 
bool removePassiveJoints ()
 Function to remove the passive joints from the filled maps. More...
 

Private Attributes

std::string _action_path
 
std::map< std::string, std::vector< std::string > > _finger_joint_map
 
std::vector< int > _fingers_group_id
 
std::vector< std::string > _fingers_names
 
int _fingers_num = 0
 
bool _is_initialized = false
 
std::map< std::string, std::string > _joint_finger_map
 
int _joints_num = 0
 
ros::NodeHandle _nh
 
KDL::Tree _robot_tree
 
std::string _srdf_path
 
std::string _srdf_string
 
srdf::Model _srdfdom
 
std::map< std::string, urdf::JointConstSharedPtr > _urdf_joint_map
 
urdf::ModelInterfaceSharedPtr _urdf_model
 
std::string _urdf_path
 
std::string _urdf_string
 

Detailed Description

Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementation and the EEInterface.

Definition at line 46 of file Parser.h.

Member Typedef Documentation

◆ ConstPtr

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

Definition at line 51 of file Parser.h.

◆ Ptr

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

Definition at line 50 of file Parser.h.

Constructor & Destructor Documentation

◆ Parser()

ROSEE::Parser::Parser ( const ros::NodeHandle nh)

Definition at line 22 of file Parser.cpp.

◆ ~Parser()

ROSEE::Parser::~Parser ( )
virtual

Definition at line 28 of file Parser.cpp.

Member Function Documentation

◆ addNotInFingerJoints()

void ROSEE::Parser::addNotInFingerJoints ( )
private

Definition at line 172 of file Parser.cpp.

◆ configure()

bool ROSEE::Parser::configure ( )
private

configure the ROSEE parser based on the configration files requested

Returns
bool true on success, false otherwise

Definition at line 326 of file Parser.cpp.

◆ getActionPath()

std::string ROSEE::Parser::getActionPath ( ) const

get the path where emit and parse grasping actions

Returns
the path as a string

Definition at line 464 of file Parser.cpp.

◆ getActuatedJointsNumber()

int ROSEE::Parser::getActuatedJointsNumber ( ) const

getter for the total number of actuated joints in the configuration files

Returns
int the number of actuated joints in the End-Effector

Definition at line 420 of file Parser.cpp.

◆ getEndEffectorName()

std::string ROSEE::Parser::getEndEffectorName ( ) const

getter for the configure End-Effector name

Returns
std::string the End-Effector name as reported in the URDF robot name

Definition at line 450 of file Parser.cpp.

◆ getFingerJointMap() [1/2]

std::map< std::string, std::vector< std::string > > ROSEE::Parser::getFingerJointMap ( ) const

getter for a description of the End-Effector as a map of finger name, finger joint names. There exists another version to get the map as reference: getFingerJointMapAsReference

Returns
std::map<std::string, std::vector<std::string>> a map respresenting an End-Effector with a key representing the finger name and the values representing a vector of joint names.

Definition at line 425 of file Parser.cpp.

◆ getFingerJointMap() [2/2]

void ROSEE::Parser::getFingerJointMap ( std::map< std::string, std::vector< std::string >> &  finger_joint_map) const

getter for the map between the finger kinematic chains and the related actuated joints, reference version of getFingerJointMap

Parameters
finger_joint_mapa map between the finger kinematic chains and the related actuated joints
Returns
void

Definition at line 440 of file Parser.cpp.

◆ getJointFingerMap() [1/2]

std::map< std::string, std::string > ROSEE::Parser::getJointFingerMap ( ) const

getter for a description of the End-Effector as a map of joint name, finger name

Returns
std::map<std::string, std::string> a map respresenting an End-Effector with a key representing the joint name and the value representing the finger which the joint belongs to

Definition at line 430 of file Parser.cpp.

◆ getJointFingerMap() [2/2]

void ROSEE::Parser::getJointFingerMap ( std::map< std::string, std::string > &  joint_finger_map) const

getter for a description of the End-Effector as a map of joint name, finger name

Parameters
joint_finger_mapa map between the joint and the related finger kinematic chain
Returns
void

Definition at line 445 of file Parser.cpp.

◆ getJointsInFinger()

bool ROSEE::Parser::getJointsInFinger ( std::string  base_link,
std::string  tip_link,
std::string  finger_name 
)
private

fill a data structure related with the revolute/prismatic joints included in between base_link and tip_link in the requested URDF

Parameters
base_linkbase link of the finger chain
tip_linktip link of the finger chain
Returns
bool true if the chain is found in the URDF, false otherwise

Definition at line 32 of file Parser.cpp.

◆ getRoseeConfigPath()

std::string ROSEE::Parser::getRoseeConfigPath ( ) const

get the filename (with path) of the yaml config file. Useful get to print infos about file parsed outside this class

Returns
a string that is the filepath of yaml config file

◆ getSrdfString()

std::string ROSEE::Parser::getSrdfString ( ) const

get the whole srdf file parsed as a string

Returns
a string containg the srdf file parsed

Definition at line 459 of file Parser.cpp.

◆ getUrdfJointMap()

std::map< std::string, urdf::JointConstSharedPtr > ROSEE::Parser::getUrdfJointMap ( ) const

getter for the URDF information of the joints of the End-Effector

Returns
std::map<std::string, urdf::JointConstSharedPtr> map between the joint name and the URDF info of the joint

Definition at line 435 of file Parser.cpp.

◆ getUrdfString()

std::string ROSEE::Parser::getUrdfString ( ) const

get the whole urdf file parsed as a string

Returns
a string containg the urdf file parsed

Definition at line 455 of file Parser.cpp.

◆ init() [1/2]

bool ROSEE::Parser::init ( )

Initialization function using the ROS param ROSEEConfigPath.

Returns
bool true for success, false otherwise

Definition at line 362 of file Parser.cpp.

◆ init() [2/2]

bool ROSEE::Parser::init ( const std::string &  urdf_path,
const std::string &  srdf_path,
const std::string &  action_path 
)

Initialization function using the path_to_cfg parameter for the path.

Parameters
urdf_pathpath to the urdf file
srdf_pathpath to the srdf file
action_pathpath to the action folder
Returns
bool true for success, false otherwise

Definition at line 380 of file Parser.cpp.

◆ parseSRDF()

bool ROSEE::Parser::parseSRDF ( )
private

Function responsible to parse the SRDF data.

Returns
bool true if the SRDF requested exists, false otherwise

Definition at line 85 of file Parser.cpp.

◆ parseURDF()

bool ROSEE::Parser::parseURDF ( )
private

Function responsible to get the file needed to fill the internal data structure of the Parser with data coming from the ros_ee configuration file requested by the user.

Returns
bool true on success, false if the config file contains errors (either in the main YAML, or in URDF, or in SRDF or in EE-HAL library path. or in the Grasping Primitive Definition). Function responsible to parse the URDF data
bool true if the URDF requested exists, false otherwise

Definition at line 225 of file Parser.cpp.

◆ printEndEffectorFingerJointsMap()

void ROSEE::Parser::printEndEffectorFingerJointsMap ( ) const

Utility to print the mapping between the End Effector finger chains and the related actuated joints.

Returns
void

Definition at line 390 of file Parser.cpp.

◆ removePassiveJoints()

bool ROSEE::Parser::removePassiveJoints ( )
private

Function to remove the passive joints from the filled maps.

Returns
bool is everything works correctly

Definition at line 196 of file Parser.cpp.

Member Data Documentation

◆ _action_path

std::string ROSEE::Parser::_action_path
private

Definition at line 173 of file Parser.h.

◆ _finger_joint_map

std::map<std::string, std::vector<std::string> > ROSEE::Parser::_finger_joint_map
private

Definition at line 187 of file Parser.h.

◆ _fingers_group_id

std::vector<int> ROSEE::Parser::_fingers_group_id
private

Definition at line 183 of file Parser.h.

◆ _fingers_names

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

Definition at line 182 of file Parser.h.

◆ _fingers_num

int ROSEE::Parser::_fingers_num = 0
private

Definition at line 181 of file Parser.h.

◆ _is_initialized

bool ROSEE::Parser::_is_initialized = false
private

Definition at line 174 of file Parser.h.

◆ _joint_finger_map

std::map<std::string, std::string> ROSEE::Parser::_joint_finger_map
private

Definition at line 188 of file Parser.h.

◆ _joints_num

int ROSEE::Parser::_joints_num = 0
private

Definition at line 185 of file Parser.h.

◆ _nh

ros::NodeHandle ROSEE::Parser::_nh
private

Definition at line 171 of file Parser.h.

◆ _robot_tree

KDL::Tree ROSEE::Parser::_robot_tree
private

Definition at line 177 of file Parser.h.

◆ _srdf_path

std::string ROSEE::Parser::_srdf_path
private

Definition at line 172 of file Parser.h.

◆ _srdf_string

std::string ROSEE::Parser::_srdf_string
private

Definition at line 172 of file Parser.h.

◆ _srdfdom

srdf::Model ROSEE::Parser::_srdfdom
private

Definition at line 179 of file Parser.h.

◆ _urdf_joint_map

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

Definition at line 189 of file Parser.h.

◆ _urdf_model

urdf::ModelInterfaceSharedPtr ROSEE::Parser::_urdf_model
private

Definition at line 176 of file Parser.h.

◆ _urdf_path

std::string ROSEE::Parser::_urdf_path
private

Definition at line 172 of file Parser.h.

◆ _urdf_string

std::string ROSEE::Parser::_urdf_string
private

Definition at line 172 of file Parser.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