ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
Classes | Public Types | Public Member Functions | Private Attributes | List of all members
ROSEE::ActionPinchLoose Class Reference

The action of pinch with two tips. More...

#include <ActionPinchLoose.h>

+ Inheritance diagram for ROSEE::ActionPinchLoose:
+ Collaboration diagram for ROSEE::ActionPinchLoose:

Classes

struct  distComp
 struct to put in order the actionStates set. More...
 

Public Types

typedef std::map< std::pair< std::string, std::string >, ActionPinchLooseMap
 
typedef std::pair< JointPos, double > StateWithDistance
 A pair to "link" the JointPos with the optional info 'distance'. More...
 
- Public Types inherited from ROSEE::ActionPrimitive
enum  Type {
  PinchTight,
  PinchLoose,
  MultiplePinchTight,
  Trig,
  TipFlex,
  FingFlex,
  SingleJointMultipleTips,
  None
}
 Enum useful to discriminate each primitive action when, for example, we want to parse a file if you change this enum, change also the ROSEEControl.msg accordingly. More...
 
typedef std::shared_ptr< ActionPrimitivePtr
 
typedef std::shared_ptr< const ActionPrimitiveConstPtr
 
- Public Types inherited from ROSEE::Action
enum  Type {
  Primitive,
  Generic,
  Composed,
  Timed,
  None
}
 Enum useful to discriminate each action when, for example, we want to parse a file if you change this enum, change also the ROSEEControl.msg accordingly. More...
 
typedef std::shared_ptr< ActionPtr
 
typedef std::shared_ptr< const ActionConstPtr
 

Public Member Functions

 ActionPinchLoose ()
 
 ActionPinchLoose (unsigned int maxStoredActionStates)
 
 ActionPinchLoose (std::string tip1, std::string tip2)
 
 ActionPinchLoose (std::pair< std::string, std::string >, JointPos, double distance)
 
JointPos getJointPos () const override
 Get the position related to this action. More...
 
JointPos getJointPos (unsigned int index) const
 
std::vector< ROSEE::JointPosgetAllJointPos () const override
 Return all the joint position stored. More...
 
std::vector< ROSEE::ActionPinchLoose::StateWithDistancegetActionStates () const
 Specific get for this action to return the state with distance info. More...
 
bool insertActionState (JointPos, double distance)
 function to insert a single action in the actionStates set of possible action. More...
 
void print () const override
 Overridable functions, if we want to make them more action-specific. More...
 
void emitYaml (YAML::Emitter &) const override
 Function to fill the argument passed with info about the action. More...
 
bool fillFromYaml (YAML::const_iterator yamlIt) override
 function to fill members of the Action with infos taken from yaml files More...
 
- Public Member Functions inherited from ROSEE::ActionPinchGeneric
 ActionPinchGeneric (std::string name, ActionPrimitive::Type type)
 KNOW the distance at a certain percentage? so se volgio prendere un oggetto largo 3 cm il programma sa quale รจ la percentage per avere una distanza di 3cm More...
 
 ActionPinchGeneric (std::string name, unsigned int maxStoredActionStates, ActionPrimitive::Type type)
 
 ActionPinchGeneric (std::string name, unsigned int nFingerInvolved, unsigned int maxStoredActionStates, ActionPrimitive::Type type)
 
std::set< std::string > getKeyElements () const override
 Necessary method to know the key used by the maps which store all the Actions of one type. More...
 
- Public Member Functions inherited from ROSEE::ActionPrimitive
virtual ~ActionPrimitive ()
 
Type getPrimitiveType () const
 
unsigned int getMaxStoredActionStates () const
 
unsigned int getnFingersInvolved () const
 
void setJointsInvolvedCount (ROSEE::JointsInvolvedCount jointsInvolvedCount)
 
- Public Member Functions inherited from ROSEE::Action
virtual ~Action ()
 
std::string getName () const
 Get the name of the action. More...
 
Type getType () const
 
std::set< std::string > getFingersInvolved () const
 Get for fingersInvolved. More...
 
JointsInvolvedCount getJointsInvolvedCount () const
 Get for jointsInvolvedCount. More...
 

Private Attributes

std::set< StateWithDistance, distCompactionStates
 For each pair, we want a set of action because we want to store (in general) more possible way to do that action. More...
 

Additional Inherited Members

- Protected Member Functions inherited from ROSEE::ActionPrimitive
 ActionPrimitive (std::string name, unsigned int maxStoredActionStates, Type type)
 
 ActionPrimitive (std::string name, unsigned int nFingersInvolved, unsigned int maxStoredActionStates, Type type)
 Protected costructor: object creable only by derived classes. More...
 
- Protected Member Functions inherited from ROSEE::Action
 Action ()
 
 Action (std::string actionName, Action::Type type)
 
- Protected Attributes inherited from ROSEE::ActionPrimitive
unsigned int nFingersInvolved
 
const unsigned int maxStoredActionStates
 
const Type primitiveType
 
- Protected Attributes inherited from ROSEE::Action
std::string name
 
Action::Type type
 
std::set< std::string > fingersInvolved
 
JointsInvolvedCount jointsInvolvedCount
 

Detailed Description

The action of pinch with two tips.

The two tips must not collide ever (otherwise we have a TightPinch). They only need to move towards each other moving the relative joints. This PinchLoose is created because also if the tips do not collide (i.e. there is not a ActionPinchTight) we can have anyway a pinch at least to take object of a certain minimum size. All the non involved fingers are set in the default state. A pinchLoose is defined by:

Definition at line 43 of file ActionPinchLoose.h.

Member Typedef Documentation

typedef std::map< std::pair<std::string, std::string>, ActionPinchLoose > ROSEE::ActionPinchLoose::Map

Definition at line 48 of file ActionPinchLoose.h.

A pair to "link" the JointPos with the optional info 'distance'.

Definition at line 53 of file ActionPinchLoose.h.

Constructor & Destructor Documentation

ROSEE::ActionPinchLoose::ActionPinchLoose ( )

Definition at line 21 of file ActionPinchLoose.cpp.

21  :
22  ActionPinchGeneric ("pinchLoose", 2, 3, ActionPrimitive::Type::PinchLoose) { }
ActionPinchGeneric(std::string name, ActionPrimitive::Type type)
KNOW the distance at a certain percentage? so se volgio prendere un oggetto largo 3 cm il programma s...
ROSEE::ActionPinchLoose::ActionPinchLoose ( unsigned int  maxStoredActionStates)

Definition at line 24 of file ActionPinchLoose.cpp.

24  :
25  ActionPinchGeneric ("pinchLoose", 2, maxStoredActionStates, ActionPrimitive::Type::PinchLoose) { }
ActionPinchGeneric(std::string name, ActionPrimitive::Type type)
KNOW the distance at a certain percentage? so se volgio prendere un oggetto largo 3 cm il programma s...
const unsigned int maxStoredActionStates
ROSEE::ActionPinchLoose::ActionPinchLoose ( std::string  tip1,
std::string  tip2 
)

Definition at line 27 of file ActionPinchLoose.cpp.

27  :
28  ActionPinchGeneric ("pinchLoose", 2, 3, ActionPrimitive::Type::PinchLoose) {
29  fingersInvolved.insert (tip1);
30  fingersInvolved.insert (tip2);
31 }
ActionPinchGeneric(std::string name, ActionPrimitive::Type type)
KNOW the distance at a certain percentage? so se volgio prendere un oggetto largo 3 cm il programma s...
std::set< std::string > fingersInvolved
Definition: Action.h:148
ROSEE::ActionPinchLoose::ActionPinchLoose ( std::pair< std::string, std::string >  tipNames,
JointPos  jp,
double  distance 
)

Definition at line 33 of file ActionPinchLoose.cpp.

34  :
35  ActionPinchGeneric ("pinchLoose", 2, 3, ActionPrimitive::Type::PinchLoose ) {
36 
37  fingersInvolved.insert (tipNames.first);
38  fingersInvolved.insert (tipNames.second);
39 
40  //different from insertState, here we are sure the set is empty (we are in costructor)
41  actionStates.insert (std::make_pair (jp, distance) );
42 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
ActionPinchGeneric(std::string name, ActionPrimitive::Type type)
KNOW the distance at a certain percentage? so se volgio prendere un oggetto largo 3 cm il programma s...
std::set< std::string > fingersInvolved
Definition: Action.h:148

Member Function Documentation

void ROSEE::ActionPinchLoose::emitYaml ( YAML::Emitter &  out) const
overridevirtual

Function to fill the argument passed with info about the action.

Pure virtual because each derived class has different infos and stored differently. check YamlWorker to correctly emit and parse the file

Parameters
outthe yaml-cpp emitter which store infos about the action
Note
this function does not print in a file, but simply fill a YAML::Emitter.

Reimplemented from ROSEE::ActionPrimitive.

Definition at line 140 of file ActionPinchLoose.cpp.

140  {
141 
142  out << YAML::Key << YAML::Flow << fingersInvolved;
143 
144  unsigned int nCont = 1;
145  out << YAML::Value << YAML::BeginMap;
146  out << YAML::Key << "PrimitiveType" << YAML::Value << primitiveType;
147  out << YAML::Key << "ActionName" << YAML::Value << name;
148  out << YAML::Key << "JointsInvolvedCount" << YAML::Value << YAML::BeginMap;
149  for (const auto &jointCount : jointsInvolvedCount ) {
150  out << YAML::Key << jointCount.first;
151  out << YAML::Value << jointCount.second;
152  }
153  out << YAML::EndMap;
154 
155  for (const auto & actionState : actionStates) { //.second is the set of ActionState
156 
157  std::string contSeq = "ActionState_" + std::to_string(nCont);
158  out << YAML::Key << contSeq;
159 
160  out << YAML::Value << YAML::BeginMap;
161  //actionState.first, the jointstates map
162  out << YAML::Key << "JointStates" << YAML::Value << YAML::BeginMap;
163  for (const auto &joint : actionState.first) {
164  out << YAML::Key << joint.first;
165  out << YAML::Value << YAML::Flow << joint.second; //vector of double is emitted like Seq
166  }
167  out << YAML::EndMap;
168 
169  //actionState.second, the optional
170  out << YAML::Key << "Optional" << YAML::Value << YAML::BeginMap;
171  out << YAML::Key << "distance" << YAML::Value << actionState.second;
172  out << YAML::EndMap;
173 
174  out << YAML::EndMap;
175  nCont++;
176  }
177  out << YAML::EndMap;
178 
179 }
std::string name
Definition: Action.h:146
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
JointsInvolvedCount jointsInvolvedCount
Definition: Action.h:149
std::set< std::string > fingersInvolved
Definition: Action.h:148
bool ROSEE::ActionPinchLoose::fillFromYaml ( YAML::const_iterator  yamlIt)
overridevirtual

function to fill members of the Action with infos taken from yaml files

Parameters
yamlIta YAML::const_iterator to the node that is loaded with YAML::LoadFile(dirPath + filename). check YamlWorker to correctly parse and emit the file

Implements ROSEE::Action.

Definition at line 182 of file ActionPinchLoose.cpp.

182  {
183 
184  std::vector <std::string> fingInvolvedVect = yamlIt->first.as <std::vector < std::string >> ();
185  for (const auto &it : fingInvolvedVect) {
186  fingersInvolved.insert(it);
187  }
188 
189  for ( YAML::const_iterator keyValue = yamlIt->second.begin(); keyValue != yamlIt->second.end(); ++keyValue) {
190 
191  std::string key = keyValue->first.as<std::string>();
192  if ( key.compare("JointsInvolvedCount") == 0 ) {
193  jointsInvolvedCount = keyValue->second.as < JointsInvolvedCount > ();
194 
195  } else if (key.compare ("ActionName") == 0 ) {
196  name = keyValue->second.as <std::string> ();
197 
198  } else if (key.compare ("PrimitiveType") == 0) {
200  keyValue->second.as <unsigned int>() );
201  if (parsedType != primitiveType ) {
202  std::cerr << "[ERROR ActionPinchLoose::" << __func__ << " parsed a type " << parsedType <<
203  " but this object has primitive type " << primitiveType << std::endl;
204  return false;
205  }
206 
207  } else if (key.compare(0, 12, "ActionState_") == 0) { //compare 12 caracters from index 0 of key
208 
209  JointPos jointPos;
210  double distance;
211  for(YAML::const_iterator asEl = keyValue->second.begin(); asEl != keyValue->second.end(); ++asEl) {
212 
213  //asEl can be the map JointStates or the map Optional
214  if (asEl->first.as<std::string>().compare ("JointStates") == 0 ) {
215  jointPos = asEl->second.as < JointPos >();
216 
217  } else if (asEl->first.as<std::string>().compare ("Optional") == 0 ) {
218  distance = asEl->second["distance"].as < double >();
219 
220  } else {
221  //ERRROr, only joinstates and optional at this level
222  std::cerr << "[ERROR ActionPinchLoose::" << __func__ << "not know key "
223  << asEl->first.as<std::string>() <<
224  " found in the yaml file at this level" << std::endl;
225  return false;
226  }
227  }
228  actionStates.insert ( std::make_pair (jointPos, distance));
229 
230  } else {
231  std::cerr << "[ERROR ActionPinchLoose::" << __func__ << "not know key " << key <<
232  " found in the yaml file" << std::endl;
233  return false;
234  }
235  }
236 
237  return true;
238 }
std::string name
Definition: Action.h:146
std::map< std::string, std::vector< double > > JointPos
The map to describe the position of all actuated joints.
Definition: Action.h:40
std::map< std::string, unsigned int > JointsInvolvedCount
The map to describe, how many times a joint is set by the action.
Definition: Action.h:63
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
Type
Enum useful to discriminate each primitive action when, for example, we want to parse a file if you ...
JointsInvolvedCount jointsInvolvedCount
Definition: Action.h:149
std::set< std::string > fingersInvolved
Definition: Action.h:148
std::vector< ROSEE::ActionPinchLoose::StateWithDistance > ROSEE::ActionPinchLoose::getActionStates ( ) const

Specific get for this action to return the state with distance info.

Returns
The vector (of size maxStoredActionStates) containing all the StateWithDistance objects

Definition at line 44 of file ActionPinchLoose.cpp.

44  {
45 
46  std::vector < ROSEE::ActionPinchLoose::StateWithDistance > retVect;
47  retVect.reserve ( actionStates.size() );
48 
49  for (auto it : actionStates ) {
50  retVect.push_back(it);
51  }
52 
53  return retVect;
54 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
std::vector< ROSEE::JointPos > ROSEE::ActionPinchLoose::getAllJointPos ( ) const
overridevirtual

Return all the joint position stored.

If the concrete (derived from Action) has only one joint position info, this function is equal to getJointPos.

Returns
vector containing all the joint pos of the action

Implements ROSEE::Action.

Definition at line 70 of file ActionPinchLoose.cpp.

70  {
71 
72  std::vector < JointPos > retVect;
73  retVect.reserve(actionStates.size());
74 
75  for (auto it : actionStates ) {
76  retVect.push_back(it.first);
77  }
78 
79  return retVect;
80 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
ROSEE::JointPos ROSEE::ActionPinchLoose::getJointPos ( ) const
overridevirtual

Get the position related to this action.

Pure Virtual function: the derived class store this info differently so they are in charge of providing the read.

Returns
JointsPos the map indicating how the position of the joint

Implements ROSEE::Action.

Definition at line 56 of file ActionPinchLoose.cpp.

56  {
57  return (actionStates.begin()->first);
58 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
ROSEE::JointPos ROSEE::ActionPinchLoose::getJointPos ( unsigned int  index) const

Definition at line 60 of file ActionPinchLoose.cpp.

60  {
61  auto it = actionStates.begin();
62  unsigned int i = 1;
63  while (i < index ) {
64  ++ it;
65  ++ i;
66  }
67  return (it->first);
68 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
bool ROSEE::ActionPinchLoose::insertActionState ( ROSEE::JointPos  jp,
double  distance 
)

function to insert a single action in the actionStates set of possible action.

If the action is not so good (based on distance) the action is not inserted and the function return false

Parameters
JointPosThe joints position
distancethe distance from the two tips.
Returns
TRUE if the action is good and is inserted in the setActionStates FALSE if the action given as param was not good as the others in the actionStates and the set was already full (maxStoredActionStates )

Definition at line 82 of file ActionPinchLoose.cpp.

82  {
83 
84  auto pairRet = actionStates.insert ( std::make_pair (jp, dist) ) ;
85 
86  if (actionStates.size() > maxStoredActionStates) {
87  //max capacity reached, we have to delete the last one
88  auto it = pairRet.first;
89 
90  if (++(it) == actionStates.end() ){
91  // the new inserted is the last one and has to be erased
92  actionStates.erase(pairRet.first);
93  return false;
94  }
95 
96  // the new inserted is not the last one that has to be erased
97  auto lastElem = actionStates.end();
98  --lastElem;
99  actionStates.erase(lastElem);
100  }
101 
102  return true;
103 }
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
const unsigned int maxStoredActionStates
void ROSEE::ActionPinchLoose::print ( ) const
overridevirtual

Overridable functions, if we want to make them more action-specific.

Reimplemented from ROSEE::Action.

Definition at line 106 of file ActionPinchLoose.cpp.

106  {
107 
108  std::stringstream output;
109 
110  output << "ActionName: " << name << std::endl;
111 
112  output << "FingersInvolved: [";
113  for (auto fingName : fingersInvolved){
114  output << fingName << ", " ;
115  }
116  output.seekp (-2, output.cur); //to remove the last comma (and space)
117  output << "]" << std::endl;
118 
119  output << "JointsInvolvedCount: " << std::endl;;
120  output << jointsInvolvedCount << std::endl;
121 
122  unsigned int nActState = 1;
123  for (auto itemSet : actionStates) { //the element in the set
124  output << "Action_State_" << nActState << " :" << std::endl;
125 
126  output << "\t" << "JointStates:" << std::endl;
127  output << itemSet.first;
128  output << "\t" << "Distance:" << std::endl;
129  output << "\t\tdistance " << itemSet.second << std::endl;
130 
131  nActState++;
132  }
133  output << std::endl;
134 
135  std::cout << output.str();
136 
137 }
std::string name
Definition: Action.h:146
std::set< StateWithDistance, distComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
JointsInvolvedCount jointsInvolvedCount
Definition: Action.h:149
std::set< std::string > fingersInvolved
Definition: Action.h:148

Member Data Documentation

std::set< StateWithDistance, distComp > ROSEE::ActionPinchLoose::actionStates
private

For each pair, we want a set of action because we want to store (in general) more possible way to do that action.

The PinchLoose among two tips can theoretically be done in infinite ways, we store the best ways found (ordering them by the distance between fingertips)

Definition at line 105 of file ActionPinchLoose.h.


The documentation for this class was generated from the following files: