Classes | Public Types | Public Member Functions | Private Attributes | List of all members
ROSEE::ActionPinchLoose Class Reference

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: More...

#include <ActionPinchLoose.h>

Inheritance diagram for ROSEE::ActionPinchLoose:
Inheritance graph
[legend]

Classes

struct  distComp
 struct to put in order the actionStates set. The first elements are the ones with lesser distance 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
typedef std::shared_ptr< const ActionPrimitiveConstPtr
 
typedef std::shared_ptr< ActionPrimitivePtr
 
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 @remind if you change this enum, change also the ROSEEControl.msg accordingly. More...
 
- Public Types inherited from ROSEE::Action
typedef std::shared_ptr< const ActionConstPtr
 
typedef std::shared_ptr< ActionPtr
 
enum  Type {
  Primitive, Generic, Composed, Timed,
  None
}
 Enum useful to discriminate each action when, for example, we want to parse a file @remind if you change this enum, change also the ROSEEControl.msg accordingly. More...
 

Public Member Functions

 ActionPinchLoose ()
 
 ActionPinchLoose (std::pair< std::string, std::string >, JointPos, double distance)
 
 ActionPinchLoose (std::string tip1, std::string tip2)
 
 ActionPinchLoose (unsigned int maxStoredActionStates)
 
void emitYaml (YAML::Emitter &) const override
 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. More...
 
bool fillFromYaml (YAML::const_iterator yamlIt) override
 function to fill members of the Action with infos taken from yaml files More...
 
std::vector< ROSEE::ActionPinchLoose::StateWithDistancegetActionStates () const
 Specific get for this action to return the state with distance info. More...
 
std::vector< ROSEE::JointPosgetAllJointPos () const override
 Return all the joint position stored. If the concrete (derived from Action) has only one joint position info, this function is equal to getJointPos. More...
 
JointPos getJointPos () const override
 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. More...
 
JointPos getJointPos (unsigned int index) const
 
bool insertActionState (JointPos, 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 More...
 
void print () const override
 Overridable functions, if we want to make them more action-specific. More...
 
- Public Member Functions inherited from ROSEE::ActionPinchGeneric
 ActionPinchGeneric (std::string name, ActionPrimitive::Type type)
 
 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. Used by YamlWorker. More...
 
- Public Member Functions inherited from ROSEE::ActionPrimitive
unsigned int getMaxStoredActionStates () const
 
unsigned int getnFingersInvolved () const
 
Type getPrimitiveType () const
 
void setJointsInvolvedCount (ROSEE::JointsInvolvedCount jointsInvolvedCount)
 
virtual ~ActionPrimitive ()
 
- Public Member Functions inherited from ROSEE::Action
std::set< std::string > getFingersInvolved () const
 Get for fingersInvolved. More...
 
JointsInvolvedCount getJointsInvolvedCount () const
 Get for jointsInvolvedCount. More...
 
std::string getName () const
 Get the name of the action. More...
 
Type getType () const
 
virtual ~Action ()
 

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. 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) 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. There is no default costructor (without arguments) because we want to set always these members. More...
 
- Protected Member Functions inherited from ROSEE::Action
 Action ()
 
 Action (std::string actionName, Action::Type type)
 
- Protected Attributes inherited from ROSEE::ActionPrimitive
const unsigned int maxStoredActionStates
 
unsigned int nFingersInvolved
 
const Type primitiveType
 
- Protected Attributes inherited from ROSEE::Action
std::set< std::string > fingersInvolved
 
JointsInvolvedCount jointsInvolvedCount
 
std::string name
 
Action::Type type
 

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

◆ Map

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

Definition at line 48 of file ActionPinchLoose.h.

◆ StateWithDistance

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

Definition at line 53 of file ActionPinchLoose.h.

Constructor & Destructor Documentation

◆ ActionPinchLoose() [1/4]

ROSEE::ActionPinchLoose::ActionPinchLoose ( )

Definition at line 21 of file ActionPinchLoose.cpp.

◆ ActionPinchLoose() [2/4]

ROSEE::ActionPinchLoose::ActionPinchLoose ( unsigned int  maxStoredActionStates)

Definition at line 24 of file ActionPinchLoose.cpp.

◆ ActionPinchLoose() [3/4]

ROSEE::ActionPinchLoose::ActionPinchLoose ( std::string  tip1,
std::string  tip2 
)

Definition at line 27 of file ActionPinchLoose.cpp.

◆ ActionPinchLoose() [4/4]

ROSEE::ActionPinchLoose::ActionPinchLoose ( std::pair< std::string, std::string >  tipNames,
JointPos  jp,
double  distance 
)

Definition at line 33 of file ActionPinchLoose.cpp.

Member Function Documentation

◆ emitYaml()

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.

◆ fillFromYaml()

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.

◆ getActionStates()

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.

◆ getAllJointPos()

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.

◆ getJointPos() [1/2]

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.

◆ getJointPos() [2/2]

ROSEE::JointPos ROSEE::ActionPinchLoose::getJointPos ( unsigned int  index) const

Definition at line 60 of file ActionPinchLoose.cpp.

◆ insertActionState()

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.

◆ print()

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.

Member Data Documentation

◆ actionStates

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:


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