Go to the documentation of this file.
18 #ifndef __ROSEE_PARSER__
19 #define __ROSEE_PARSER__
31 #include <yaml-cpp/yaml.h>
32 #include <urdf_parser/urdf_parser.h>
37 #include <boost/filesystem/path.hpp>
50 typedef std::shared_ptr<Parser>
Ptr;
51 typedef std::shared_ptr<const Parser>
ConstPtr;
73 bool init (
const std::string& urdf_path,
const std::string& srdf_path,
const std::string& action_path );
81 std::map<std::string, urdf::JointConstSharedPtr>
getUrdfJointMap()
const;
98 void getFingerJointMap(std::map<std::string, std::vector<std::string>>& finger_joint_map)
const;
117 void getJointFingerMap(std::map<std::string, std::string>& joint_finger_map)
const;
243 bool getJointsInFinger(std::string base_link, std::string tip_link, std::string finger_name);
249 #endif // __ROSEE_PARSER__
std::map< std::string, std::vector< std::string > > _finger_joint_map
std::map< std::string, std::string > _joint_finger_map
std::string getEndEffectorName() const
getter for the configure End-Effector name
void addNotInFingerJoints()
bool removePassiveJoints()
Function to remove the passive joints from the filled maps.
std::vector< int > _fingers_group_id
std::map< std::string, urdf::JointConstSharedPtr > getUrdfJointMap() const
getter for the URDF information of the joints of the End-Effector
std::shared_ptr< const Parser > ConstPtr
std::map< std::string, std::string > getJointFingerMap() const
getter for a description of the End-Effector as a map of joint name, finger name
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....
std::string getSrdfString() const
get the whole srdf file parsed as a string
std::vector< std::string > _fingers_names
std::map< std::string, urdf::JointConstSharedPtr > _urdf_joint_map
bool parseSRDF()
Function responsible to parse the SRDF data.
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 ti...
urdf::ModelInterfaceSharedPtr _urdf_model
std::string getActionPath() const
get the path where emit and parse grasping actions
std::shared_ptr< Parser > Ptr
Parser(const ros::NodeHandle &nh)
std::string getUrdfString() const
get the whole urdf file parsed as a string
bool init()
Initialization function using the ROS param ROSEEConfigPath.
void printEndEffectorFingerJointsMap() const
Utility to print the mapping between the End Effector finger chains and the related actuated joints.
bool configure()
configure the ROSEE parser based on the configration files requested
std::string getRoseeConfigPath() const
get the filename (with path) of the yaml config file. Useful get to print infos about file parsed out...
int getActuatedJointsNumber() const
getter for the total number of actuated joints in the configuration files
bool parseURDF()
Function responsible to get the file needed to fill the internal data structure of the Parser with da...
Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementati...
end-effector
Author(s): Luca Muratore
, Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26