25 std::cerr <<
"[ERROR MapActionHandler::" << __func__ <<
"] Not found any primitive action with name " << primitiveName << std::endl;
34 std::vector<ROSEE::MapActionHandler::ActionPrimitiveMap> vectRet;
38 if (it.second.begin()->second->getPrimitiveType() == type ){
39 vectRet.push_back(it.second);
56 if (map.size() == 0 ) {
60 if (map.begin()->second->getKeyElements().size() != key.size()) {
61 std::cerr <<
"[ERROR MapActionHandler::" << __func__ <<
"] The action '" 62 << primitiveName <<
"' has as key a set of dimension " <<
63 map.begin()->second->getKeyElements().size() <<
64 " and not dimension of passed 2nd argument " << key.size() << std::endl;
68 auto it = map.find(key);
70 if (it == map.end()) {
71 std::cerr <<
"[ERROR MapActionHandler::" << __func__ <<
"] Not found any action '" 72 << primitiveName <<
"' with key [ " ;
73 for (
auto keyEl : key) {
74 std::cerr << keyEl <<
", ";
76 std::cerr <<
"] " << std::endl;
85 std::set <std::string> keySet (key.begin(), key.end());
91 std::set <std::string> keySet {key};
97 std::set <std::string> keySet {key.first, key.second};
106 std::vector <ActionPrimitiveMap> theMaps;
107 for (
int i =0; i<maps.size(); i++) {
108 if (maps.at(i).begin()->second->getKeyElements().size() == key.size()) {
109 theMaps.push_back(maps.at(i));
113 if (theMaps.size() == 0 ) {
114 std::cerr <<
"[ERROR MapActionHandler::" << __func__ <<
"] No primitive action of type '" 115 << type <<
"' has as key a set of dimension " <<
116 key.size() <<
" (passed 2nd argument)" << std::endl;
117 return std::vector<ROSEE::ActionPrimitive::Ptr>();
127 std::vector<ROSEE::ActionPrimitive::Ptr> returnVect;
128 for (
auto action : theMaps) {
129 auto it = action.find(key);
130 if (it != action.end()) {
131 returnVect.push_back(it->second);
135 if (returnVect.size() == 0) {
136 std::cerr <<
"[ERROR MapActionHandler::" << __func__ <<
"] Not found any primitive action of type '" << type <<
"' with key [ " ;
137 for (
auto keyEl : key) {
138 std::cerr << keyEl <<
", ";
140 std::cerr <<
"] " << std::endl;
141 return std::vector<ROSEE::ActionPrimitive::Ptr>();
150 std::set <std::string> keySet (key.begin(), key.end());
156 std::set <std::string> keySet {key};
162 std::set <std::string> keySet {key.first, key.second};
179 std::cerr <<
"[ERROR MapActionHandler " << __func__ <<
"] No generic function named '" << name <<
"'" << std::endl;
193 auto it =
timeds.find(name);
194 if (it ==
timeds.end() ) {
195 std::cerr <<
"[ERROR MapActionHandler " << __func__ <<
"] No timed function named '" << name <<
"'" << std::endl;
209 std::map<std::string, ROSEE::ActionPrimitive::Ptr> ret;
213 if (it.second.begin()->second->getPrimitiveType() ==
214 ROSEE::ActionPrimitive::Type::SingleJointMultipleTips &&
215 it.second.begin()->second->getnFingersInvolved() == nFingers){
218 for (
auto itt : it.second) {
220 std::string key = *(itt.first.begin());
221 ret.insert(std::make_pair(key, itt.second));
227 if (ret.size() == 0) {
228 std::cerr <<
"[WARNING MapActionHandler::" << __func__ <<
"] Not found any singleJointMultipleTips action that moves " << nFingers <<
" fingers " << std::endl;
242 if (moreTip.size() == 1) {
243 return moreTip.begin()->second;
246 std::cerr <<
"[WARNING MapActionHandler::" << __func__ <<
"] Not found any grasp named " << graspName <<
" neither a singleJointMultipleTips primitive " 247 <<
"that move all fingers with a single joint, you should create one action for grasp before calling parseAllActions/parseAllGenerics()" 258 std::set <std::string> pairedFinger;
262 case ROSEE::ActionPrimitive::Type::PinchTight : {
267 pairedFinger = it->second;
270 std::cerr <<
"[WARNING MapActionHandler " << __func__ <<
"] No companions found to make a tight pinch with " << finger <<
" finger" 276 case ROSEE::ActionPrimitive::Type::PinchLoose : {
281 pairedFinger = it->second;
284 std::cerr <<
"[WARNING MapActionHandler " << __func__ <<
"] No companions found to make a loose pinch with " << finger <<
" finger" 292 std::cerr <<
"[WARNING MapActionHandler " << __func__ <<
"] Type " <<
293 pinchType <<
" is not a type to look for companions " << std::endl;
323 for (
auto file : filenames) {
325 primitives.insert (std::make_pair( primitive.begin()->second->getName(), primitive) ) ;
338 for (
auto file : filenames) {
342 generics.insert (std::make_pair( genericPointer->getName(), genericPointer) ) ;
355 for (
auto file : filenames) {
357 std::shared_ptr < ROSEE::ActionTimed > timed = yamlWorker.
parseYamlTimed(pathFolder+file);
358 timeds.insert (std::make_pair( timed->getName(), timed) ) ;
367 auto it =
generics.find(generic->getName());
371 std::cerr <<
"[ERROR MapActionHandler " << __func__ <<
"] Trying to insert generic action with name " <<
372 generic->getName() <<
"which already exists" << std::endl;
378 generics.insert(it, std::make_pair(generic->getName(),
generic));
394 if (maps.size() != 0 ){
396 for (
auto mapEl : map) {
398 for (
auto fing : mapEl.first) {
412 it.second.erase(it.first);
417 auto mapsloose =
getPrimitiveMap(ROSEE::ActionPrimitive::Type::PinchLoose);
419 if (mapsloose.size() != 0 ) {
421 for (
auto mapEl : map) {
423 for (
auto fing : mapEl.first) {
437 it.second.erase(it.first);
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > parseYamlPrimitive(std::string fileWithPath)
Parse a yaml file and return the map with all the actions present in the file.
std::shared_ptr< ROSEE::ActionTimed > parseYamlTimed(std::string fileWithPath)
Parse a timed Action.
std::map< std::string, std::set< std::string > > getPinchTightPairsMap() const
ROSEE::ActionGeneric::Ptr parseYamlGeneric(std::string fileWithPath)
static std::vector< std::string > getFilesInDir(std::string pathFolder)
std::set< std::string > getFingertipsForPinch(std::string finger, ROSEE::ActionPrimitive::Type pinchType) const
std::map< std::string, std::set< std::string > > getPinchLoosePairsMap() const
std::map< std::string, std::set< std::string > > pinchLoosePairsMap
std::map< std::string, std::shared_ptr< ROSEE::ActionGeneric > > getAllGenerics() const
std::shared_ptr< ActionGeneric > Ptr
std::shared_ptr< ActionPrimitive > Ptr
bool parseAllPrimitives(std::string pathFolder)
std::vector< ActionPrimitiveMap > getPrimitiveMap(ROSEE::ActionPrimitive::Type type) const
getter to take all the primitives maps of one type (
bool parseAllGenerics(std::string pathFolder)
std::map< std::string, std::shared_ptr< ROSEE::ActionTimed > > timeds
std::shared_ptr< ROSEE::ActionGeneric > getGeneric(std::string name, bool verbose=true) const
Type
Enum useful to discriminate each primitive action when, for example, we want to parse a file if you ...
std::map< std::string, ActionPrimitiveMap > primitives
std::map< std::string, ROSEE::ActionPrimitive::Ptr > getPrimitiveSingleJointMultipleTipsMap(unsigned int nFingers) const
function to return the map that contains all the singleJointMultipleTips primitive with that moves th...
ROSEE::ActionPrimitive::Ptr getPrimitive(std::string primitiveName, std::set< std::string > key) const
std::shared_ptr< ROSEE::ActionTimed > getTimed(std::string name) const
bool insertSingleGeneric(ROSEE::ActionGeneric::Ptr generic)
This is needed by rosservicehandler which has to include a new doable action, if received the service...
std::shared_ptr< Action > Ptr
ROSEE::Action::Ptr getGrasp(unsigned int nFingers, std::string graspName="grasp")
This function try to get an action that should be a grasp.
bool parseAllActions(std::string pathFolder)
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > ActionPrimitiveMap
std::map< std::string, std::shared_ptr< ROSEE::ActionTimed > > getAllTimeds() const
bool parseAllTimeds(std::string pathFolder)
std::map< std::string, std::shared_ptr< ROSEE::ActionGeneric > > generics
std::map< std::string, std::set< std::string > > pinchTightPairsMap
std::map< std::string, ActionPrimitiveMap > getAllPrimitiveMaps() const