FindActions.h
Go to the documentation of this file.
1 #ifndef __ROSEE_FIND_ACTIONS_
2 #define __ROSEE_FIND_ACTIONS_
3 
5 
14 
15 #include <muParser.h>
16 
17 
18 #define N_EXP_COLLISION 5000 //5000 is ok
19 #define N_EXP_DISTANCES 5000 //? is ok
20 #define N_EXP_COLLISION_MULTPINCH 3000
21 #define DEFAULT_JOINT_POS 0.0
22 
23 namespace ROSEE
24 {
25 
37 {
38 public:
39  FindActions ( std::shared_ptr < ROSEE::ParserMoveIt > parserMoveit ) ;
40 
47  std::pair < std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchTight >,
48  std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose > >
49  findPinch ( std::string path2saveYaml );
50 
65  std::map < std::set <std::string>, ROSEE::ActionMultiplePinchTight > findMultiplePinch (
66  unsigned int nFinger, std::string path2saveYaml, bool strict = true );
67 
77  std::map <std::string, ROSEE::ActionTrig> findTrig ( ROSEE::ActionPrimitive::Type actionType,
78  std::string path2saveYaml );
79 
80  std::map < std::string, ROSEE::ActionSingleJointMultipleTips> findSingleJointMultipleTips ( unsigned int nFinger, std::string path2saveYaml );
81 
82 private:
83 
84  std::shared_ptr < ROSEE::ParserMoveIt > parserMoveIt;
85 
86  //lets store this, we access at each setRandomPos
87  std::map<std::string, std::pair<std::string, std::string>> mimicNLRelMap;
88 
94  std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchTight > checkCollisions();
95 
100  void checkDistances (std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose >* mapOfLoosePinches);
101 
116  std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose >* mapOfLoosePinches);
117 
145  std::map <std::set<std::string>, ROSEE::ActionMultiplePinchTight>
146  checkCollisionsForMultiplePinch(unsigned int nFinger, bool strict);
147 
153  void removeBoundsOfNotCollidingTips ( const std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose >* mapOfLoosePinches,
154  robot_model::RobotModelPtr kinematic_model_noBound);
155 
166  void fillNotCollidingTips ( std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose >* mapOfLoosePinches,
167  const std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchTight >* mapOfPinches );
168 
180  std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchTight >* mapOfPinches,
181  std::map < std::pair <std::string, std::string> , ROSEE::ActionPinchLoose >* mapOfLoosePinches) ;
182 
183 
193  std::map <std::string, ActionTrig> trig();
194 
206  std::map <std::string, ROSEE::ActionTrig> tipFlex();
207 
217  std::map <std::string, ROSEE::ActionTrig> fingFlex();
218 
219 
233  bool insertJointPosForTrigInMap ( std::map <std::string, ActionTrig>& trigMap,
234  ROSEE::ActionTrig action, std::string jointName, double trigValue);
235 
236 
237 
244  ROSEE::JointsInvolvedCount setOnlyDependentJoints(std::pair < std::string, std::string > tipsNames, JointPos *jPos);
245 
246 
254  ROSEE::JointsInvolvedCount setOnlyDependentJoints( std::set< std::string > tipsNames,
255  JointPos *jPos);
256 
262  JointPos getConvertedJointPos(const robot_state::RobotState* kinematic_state);
263 
264 
271 
278  std::pair < std::string, std::string > getFingersPair (std::pair <std::string, std::string> tipsPair) const;
279 
287  std::set <std::string> getFingersSet (std::set <std::string> tipsSet) const;
288 
296  std::pair < std::string, std::string > getFingertipsPair (std::pair <std::string, std::string> fingersPair) const;
297 
308  void setToRandomPositions(robot_state::RobotState* kinematic_state);
309 
310 
311 };
312 
313 }
314 
315 
316 #endif //__ROSEE_FIND_ACTIONS_
ROSEE::FindActions::mimicNLRelMap
std::map< std::string, std::pair< std::string, std::string > > mimicNLRelMap
Definition: FindActions.h:87
ROSEE::FindActions::findMultiplePinch
std::map< std::set< std::string >, ROSEE::ActionMultiplePinchTight > findMultiplePinch(unsigned int nFinger, std::string path2saveYaml, bool strict=true)
Finder for MultiplePinch (a pinch done with more than 2 finger). This function return the found multp...
Definition: FindActions.cpp:214
ROSEE::FindActions::getFingertipsPair
std::pair< std::string, std::string > getFingertipsPair(std::pair< std::string, std::string > fingersPair) const
Given the fingersPair, this function return the pair of their fingers, in lexicographical order.
Definition: FindActions.cpp:929
ROSEE::FindActions::checkDistances
void checkDistances(std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > *mapOfLoosePinches)
Principal function which fill the mapOfLoosePinches basing on minumun distance between tips.
Definition: FindActions.cpp:334
ROSEE::FindActions::checkWhichTipsCollideWithoutBounds
void checkWhichTipsCollideWithoutBounds(std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > *mapOfLoosePinches)
Function similar to checkCollisions but used for Loose Pinches. First, we temporarily remove bounds o...
Definition: FindActions.cpp:445
ROSEE::FindActions::fillNotCollidingTips
void fillNotCollidingTips(std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > *mapOfLoosePinches, const std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchTight > *mapOfPinches)
function to "initialize" the map of ActionPinchLoose mapOfLoosePinches. It is done adding all the tip...
Definition: FindActions.cpp:719
ROSEE
Definition: EEInterface.h:30
YamlWorker.h
ROSEE::JointsInvolvedCount
std::map< std::string, unsigned int > JointsInvolvedCount
The map to describe, how many times a joint is set by the action. An ActionPrimitive and an ActionCom...
Definition: Action.h:63
ROSEE::FindActions::insertJointPosForTrigInMap
bool insertJointPosForTrigInMap(std::map< std::string, ActionTrig > &trigMap, ROSEE::ActionTrig action, std::string jointName, double trigValue)
Insert/update an ActionTrig in the trigMap. This is done setting the jointName position to the given ...
Definition: FindActions.cpp:667
ROSEE::ActionPinchTight
The action of pinch with two tips. The two tips must collide for some hand configuration to mark this...
Definition: ActionPinchTight.h:40
moveit::core::RobotState
ROSEE::FindActions::setToDefaultPositionPassiveJoints
void setToDefaultPositionPassiveJoints(moveit::core::RobotState *kinematic_state)
set to DEFAULT_JOINT_POS all the passive joints (defined so in the urdf file). this is necessary beca...
Definition: FindActions.cpp:817
ROSEE::FindActions::setToRandomPositions
void setToRandomPositions(robot_state::RobotState *kinematic_state)
This function set the random position of joint considering:
Definition: FindActions.cpp:826
Action.h
ROSEE::FindActions::getFingersPair
std::pair< std::string, std::string > getFingersPair(std::pair< std::string, std::string > tipsPair) const
Giving as argument a pair of fingertips, this function return a pair of fingers that are the fingers ...
Definition: FindActions.cpp:887
ROSEE::FindActions::findTrig
std::map< std::string, ROSEE::ActionTrig > findTrig(ROSEE::ActionPrimitive::Type actionType, std::string path2saveYaml)
Function to look for trigs (trig, tipFlex and fingFlex). The type of trig to be looked for is choosen...
Definition: FindActions.cpp:73
ROSEE::ActionMultiplePinchTight
Class to describe the action of "pinching" with more than 2 tips (with 2 tips there is the ActionPinc...
Definition: ActionMultiplePinchTight.h:48
ROSEE::FindActions
Class to check which fingertips collide (for the pinch action at the moment)
Definition: FindActions.h:36
ActionPinchTight.h
ParserMoveIt.h
ROSEE::FindActions::findSingleJointMultipleTips
std::map< std::string, ROSEE::ActionSingleJointMultipleTips > findSingleJointMultipleTips(unsigned int nFinger, std::string path2saveYaml)
Definition: FindActions.cpp:137
ActionSingleJointMultipleTips.h
ActionTrig.h
ROSEE::FindActions::fingFlex
std::map< std::string, ROSEE::ActionTrig > fingFlex()
We start from each tip. Given a tip, we check if ParserMoveIt::getNExclusiveJointsOfTip >= 2 (see tip...
Definition: FindActions.cpp:637
ROSEE::ActionTrig
The action of moving some joints (see later) of a single finger in a full clousure position towards t...
Definition: ActionTrig.h:64
ROSEE::FindActions::getFingersSet
std::set< std::string > getFingersSet(std::set< std::string > tipsSet) const
Function used when looking for multiple pinches. It returns the set containing the fingers of the pas...
Definition: FindActions.cpp:909
ROSEE::FindActions::getConvertedJointPos
JointPos getConvertedJointPos(const robot_state::RobotState *kinematic_state)
Utility function to take the actuated joint positions from a kinematic_state and returns the same inf...
Definition: FindActions.cpp:705
ROSEE::FindActions::setOnlyDependentJoints
ROSEE::JointsInvolvedCount setOnlyDependentJoints(std::pair< std::string, std::string > tipsNames, JointPos *jPos)
Given the contact, we want to know the state of the joint to replicate it. But we want to know only t...
Definition: FindActions.cpp:746
ROSEE::FindActions::tipFlex
std::map< std::string, ROSEE::ActionTrig > tipFlex()
We start from each tip. Given a tip, we look for all the joints that move this tip....
Definition: FindActions.cpp:605
ROSEE::FindActions::checkCollisionsForMultiplePinch
std::map< std::set< std::string >, ROSEE::ActionMultiplePinchTight > checkCollisionsForMultiplePinch(unsigned int nFinger, bool strict)
support function for findMultiplePinch (a pinch done with more than 2 finger). This is done similarly...
Definition: FindActions.cpp:499
ROSEE::FindActions::trig
std::map< std::string, ActionTrig > trig()
trig is the action of closing a SINGLE finger towards the palm. The position is the bound which is fa...
Definition: FindActions.cpp:577
planning_scene.h
ROSEE::FindActions::removeBoundsOfNotCollidingTips
void removeBoundsOfNotCollidingTips(const std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > *mapOfLoosePinches, robot_model::RobotModelPtr kinematic_model_noBound)
Support function to remove the joint limits from the model. This is done when looking for Loose Pinch...
Definition: FindActions.cpp:363
ROSEE::ActionPrimitive::Type
Type
Enum useful to discriminate each primitive action when, for example, we want to parse a file @remind ...
Definition: ActionPrimitive.h:60
ActionMultiplePinchTight.h
ROSEE::ActionPinchLoose
The action of pinch with two tips. The two tips must not collide ever (otherwise we have a TightPinch...
Definition: ActionPinchLoose.h:43
ROSEE::FindActions::changeFingertipsToFingerNames
void changeFingertipsToFingerNames(std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchTight > *mapOfPinches, std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > *mapOfLoosePinches)
this function take the two tight and loose maps and change the keys from fingertips names to their fi...
ROSEE::FindActions::FindActions
FindActions(std::shared_ptr< ROSEE::ParserMoveIt > parserMoveit)
Definition: FindActions.cpp:3
ROSEE::FindActions::findPinch
std::pair< std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchTight >, std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchLoose > > findPinch(std::string path2saveYaml)
Function to look for pinches, both Tight and Loose ones. It fill the maps (returned as pair),...
Definition: FindActions.cpp:13
ROSEE::FindActions::parserMoveIt
std::shared_ptr< ROSEE::ParserMoveIt > parserMoveIt
Definition: FindActions.h:84
ROSEE::JointPos
std::map< std::string, std::vector< double > > JointPos
The map to describe the position of all actuated joints. The key is the name of the string,...
Definition: Action.h:40
ActionPinchLoose.h
ROSEE::FindActions::checkCollisions
std::map< std::pair< std::string, std::string >, ROSEE::ActionPinchTight > checkCollisions()
principal function which check for collisions with moveit functions when looking for tight pinches
Definition: FindActions.cpp:249


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26