|
| MapActionHandler () |
|
bool | parseAllPrimitives (std::string pathFolder) |
|
bool | parseAllGenerics (std::string pathFolder) |
|
bool | parseAllTimeds (std::string pathFolder) |
|
bool | parseAllActions (std::string pathFolder) |
|
std::vector< ActionPrimitiveMap > | getPrimitiveMap (ROSEE::ActionPrimitive::Type type) const |
| getter to take all the primitives maps of one type ( More...
|
|
ActionPrimitiveMap | getPrimitiveMap (std::string primitiveName) const |
|
std::map< std::string, ActionPrimitiveMap > | getAllPrimitiveMaps () const |
|
ROSEE::ActionPrimitive::Ptr | getPrimitive (std::string primitiveName, std::set< std::string > key) const |
|
std::vector< ROSEE::ActionPrimitive::Ptr > | getPrimitive (ROSEE::ActionPrimitive::Type, std::set< std::string > key) const |
|
ROSEE::ActionPrimitive::Ptr | getPrimitive (std::string primitiveName, std::vector< std::string > key) const |
|
std::vector< ROSEE::ActionPrimitive::Ptr > | getPrimitive (ROSEE::ActionPrimitive::Type, std::vector< std::string > key) const |
|
ROSEE::ActionPrimitive::Ptr | getPrimitive (std::string primitiveName, std::pair< std::string, std::string > key) const |
|
std::vector< ROSEE::ActionPrimitive::Ptr > | getPrimitive (ROSEE::ActionPrimitive::Type, std::pair< std::string, std::string > key) const |
|
ROSEE::ActionPrimitive::Ptr | getPrimitive (std::string primitiveName, std::string key) const |
|
std::vector< ROSEE::ActionPrimitive::Ptr > | getPrimitive (ROSEE::ActionPrimitive::Type, std::string key) const |
|
std::shared_ptr< ROSEE::ActionGeneric > | getGeneric (std::string name, bool verbose=true) const |
|
std::map< std::string, std::shared_ptr< ROSEE::ActionGeneric > > | getAllGenerics () const |
|
std::shared_ptr< ROSEE::ActionTimed > | getTimed (std::string name) const |
|
std::map< std::string, std::shared_ptr< ROSEE::ActionTimed > > | getAllTimeds () const |
|
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 the specific number of fingers nFingers . More...
|
|
ROSEE::Action::Ptr | getGrasp (unsigned int nFingers, std::string graspName="grasp") |
| This function try to get an action that should be a grasp. More...
|
|
std::set< std::string > | getFingertipsForPinch (std::string finger, ROSEE::ActionPrimitive::Type pinchType) const |
|
std::map< std::string, std::set< std::string > > | getPinchTightPairsMap () const |
|
std::map< std::string, std::set< std::string > > | getPinchLoosePairsMap () const |
|
bool | insertSingleGeneric (ROSEE::ActionGeneric::Ptr generic) |
| This is needed by rosservicehandler which has to include a new doable action, if received the service. More...
|
|
- Todo:
- write docs
Definition at line 39 of file MapActionHandler.h.
ROSEE::Action::Ptr ROSEE::MapActionHandler::getGrasp |
( |
unsigned int |
nFingers, |
|
|
std::string |
graspName = "grasp" |
|
) |
| |
This function try to get an action that should be a grasp.
A real grasp, until now, can be two things:
- a generic/composed action, composed by trig with all the fingers
- a SingleJointMultipleTips primitive action, where the number of fingers moved is obviously the number of finger of the hand In the second case, if we have more joints that moves all the fingers, we return no action because we do not know which one is "the grasp". If we have only one joint that move all fingers, we return the singleJointMultipleTips action associated with this joint, even if there is the possibility that this is not a grasp (but which hand has only one joint that moves all fingers and it is not for a grasp?)
This function look first for a generic (or composed, that is a derived class of generic) action with name graspName
, that should have been created and emitted before calling the parseAllActions (or parseAllGenerics) (e.g. in UniversalFindActions putting all the trigs togheter, but we can also define the grasp in another way).
- Parameters
-
nFingers | the number of the finger of the hand, that is an information that this class hasn't |
graspName | name given to the action grasp, default is "grasp" |
- Returns
- pointer to Action, because the pointed object can be a primitive or a generic action.
- Todo:
- If not found, it tries to create a composed action, done with all trigs, and store this new action??
- Warning
- Generic and singleJointMultipleTips are different ros msg: singleJointMultipleTips want a element to be set (the joint) so this can cause problems.. so maybe this function should not exist
Definition at line 234 of file MapActionHandler.cpp.
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()" 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...
std::map< std::string, std::shared_ptr< ROSEE::ActionGeneric > > generics
std::map< std::string, ROSEE::ActionPrimitive::Ptr > ROSEE::MapActionHandler::getPrimitiveSingleJointMultipleTipsMap |
( |
unsigned int |
nFingers | ) |
const |
function to return the map that contains all the singleJointMultipleTips primitive with that moves the specific number of fingers nFingers
.
This is in practice, the file singleJointMultipleTips_*nFingers*.yaml
It return only one map because per definition we have only one ActionPrimitiveMap of type singleJointMultipleTips with a defined number of nFinger. (Then inside it we can have more primitives ( when we have a hand with more joints that moves more than 1 finger), but always with the same number of nFinger)
- Parameters
-
nFingers | the number of the finger that the singleJointMultipleTips primitives moves |
- Returns
- A map with key the joint that moves the
nFingers
and as value the primitive with all the info to command it to the hand. Obvioulsy we can have more joints that move a certain number (nFingers
) of fingers
- Todo:
- return with the key as set instead??? or leave as it is?
Definition at line 207 of file MapActionHandler.cpp.
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;
std::map< std::string, ActionPrimitiveMap > primitives