ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
Namespaces | Classes | Typedefs | Functions
ROSEE Namespace Reference

Namespaces

 Utils
 

Classes

class  Action
 The pure virtual class representing an Action. More...
 
class  ActionComposed
 A ActionComposed, which is formed by one or more Primitives (or even other composed). More...
 
class  ActionGeneric
 Class to handle a generic, simple action. More...
 
class  ActionMultiplePinchTight
 Class to describe the action of "pinching" with more than 2 tips (with 2 tips there is the ActionPinchTight and ActionPinchLoose The number of the finger used is fixed when the object is costructed, and it is stored in the father member nFingersInvolved. More...
 
class  ActionPinchGeneric
 A base virtual class for the PinchTight and PinchLoose classes. More...
 
class  ActionPinchLoose
 The action of pinch with two tips. More...
 
class  ActionPinchTight
 The action of pinch with two tips. More...
 
class  ActionPrimitive
 Virtual class, Base of all the primitive actions. More...
 
class  ActionSingleJointMultipleTips
 Primitive which indicate a motion of n fingers moving ONLY ONE joint. More...
 
class  ActionTimed
 An action composed by other ones that must be executed one after other with some wait time (also 0) in between. More...
 
class  ActionTrig
 The action of moving some joints (see later) of a single finger in a full clousure position towards the palm. More...
 
class  DummyHal
 Class representing an end-effector. More...
 
class  EEHal
 Class representing an end-effector. More...
 
class  EEInterface
 Class representing and End-Effector. More...
 
class  FindActions
 Class to check which fingertips collide (for the pinch action at the moment) More...
 
class  MapActionHandler
 
class  Parser
 Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementation and the EEInterface. More...
 
class  ParserMoveIt
 class to parse urdf and srdf with moveit classes and to give information about the model parsed More...
 
class  RosActionServer
 
class  RosServiceHandler
 
class  UniversalRosEndEffectorExecutor
 Class representing the ROS executor implementing the unviversal ROS EE concept. More...
 
class  XBot2Hal
 Concrete class which communicate directly with ROS topics. More...
 
class  YamlWorker
 

Typedefs

typedef std::map< std::string, std::vector< double > > JointPos
 The map to describe the position of all actuated joints. More...
 
typedef std::map< std::string, unsigned int > JointsInvolvedCount
 The map to describe, how many times a joint is set by the action. More...
 

Functions

std::ostream & operator<< (std::ostream &output, const JointPos jp)
 operator overload for JointPos so it is easier to print More...
 
JointPos operator* (double multiplier, JointPos jp)
 
JointPos operator* (JointPos jp, double multiplier)
 
JointPosoperator*= (JointPos &jp, double multiplier)
 
JointPos operator+ (JointPos jp1, JointPos jp2)
 
JointPosoperator+= (JointPos &jp1, ROSEE::JointPos jp2)
 
std::ostream & operator<< (std::ostream &output, const JointsInvolvedCount jic)
 
std::ostream & operator<< (std::ostream &out, const ROSEE::Action::Type type)
 To print the action type enum as the real name (eg primitive) and not as the enum number REmember to add here if new type are implemented. More...
 

Typedef Documentation

typedef std::map<std::string, std::vector <double> > ROSEE::JointPos

The map to describe the position of all actuated joints.

The key is the name of the string, the value is a vector of joint positions (because in general a joint can have more DOFs

Definition at line 40 of file Action.h.

typedef std::map<std::string, unsigned int> ROSEE::JointsInvolvedCount

The map to describe, how many times a joint is set by the action.

An ActionPrimitive and an ActionComposed (indipendent) have as values only 0 or 1. ActionComposed (not independet) can have values > 1. This map is also useful to understand if a joint is used or not by the action (0 == not used) so we can control only the necessary joints.

Definition at line 63 of file Action.h.

Function Documentation

ROSEE::JointPos ROSEE::operator* ( double  multiplier,
ROSEE::JointPos  jp 
)

Definition at line 36 of file Action.cpp.

36  {
37 
38  return jp *= multiplier;
39 }
ROSEE::JointPos ROSEE::operator* ( ROSEE::JointPos  jp,
double  multiplier 
)

Definition at line 41 of file Action.cpp.

41  {
42 
43  return jp *= multiplier;
44 }
ROSEE::JointPos & ROSEE::operator*= ( ROSEE::JointPos jp,
double  multiplier 
)

Definition at line 46 of file Action.cpp.

46  {
47 
48  for ( auto &jsEl : jp) {
49  for (int i = 0; i< jsEl.second.size(); i++) {
50  jsEl.second.at(i) *= multiplier;
51  }
52  }
53 
54  return jp;
55 }
ROSEE::JointPos ROSEE::operator+ ( ROSEE::JointPos  jp1,
ROSEE::JointPos  jp2 
)

Definition at line 57 of file Action.cpp.

57  {
58 
59  return jp1 += jp2;
60 }
ROSEE::JointPos & ROSEE::operator+= ( ROSEE::JointPos jp1,
ROSEE::JointPos  jp2 
)

Definition at line 62 of file Action.cpp.

62  {
63 
64  if ( ! ROSEE::Utils::keys_equal(jp1, jp2) ) {
66  }
67 
68  for (auto &jsEl : jp1) {
69  if (jsEl.second.size() != jp2.at(jsEl.first).size() ) {
70  throw "Dofs not same";
71  }
72 
73  for (int i = 0; i < jsEl.second.size(); i++) {
74  jsEl.second.at(i) += jp2.at(jsEl.first).at(i);
75  }
76  }
77 
78  return jp1;
79 }
bool keys_equal(std::map< keyType, valueType1 > const &lhs, std::map< keyType, valueType2 > const &rhs)
Return false if two maps have different keys.
Definition: Utils.h:182
std::ostream & ROSEE::operator<< ( std::ostream &  output,
const JointPos  jp 
)

operator overload for JointPos so it is easier to print

Definition at line 24 of file Action.cpp.

24  {
25  for (const auto &jsEl : jp) {
26  output << "\t\t"<<jsEl.first << " : "; //joint name
27  for(const auto &jValue : jsEl.second){
28  output << jValue << ", "; //joint position (vector because can have multiple dof)
29  }
30  output.seekp (-2, output.cur); //to remove the last comma (and space)
31  output << std::endl;
32  }
33  return output;
34 }
std::ostream & ROSEE::operator<< ( std::ostream &  output,
const JointsInvolvedCount  jic 
)

Definition at line 81 of file Action.cpp.

81  {
82  for (const auto &jicEl : jic) {
83  output << "\t"<< jicEl.first << " : " << jicEl.second;
84  output << std::endl;
85  }
86  return output;
87 }
std::ostream & ROSEE::operator<< ( std::ostream &  out,
const ROSEE::Action::Type  type 
)

To print the action type enum as the real name (eg primitive) and not as the enum number REmember to add here if new type are implemented.

Definition at line 89 of file Action.cpp.

89  {
90 
91  const char* s = 0;
92 #define PROCESS_VAL(p) case(p): s = #p; break;
93  switch(type){
94  PROCESS_VAL(ROSEE::Action::Type::Primitive);
95  PROCESS_VAL(ROSEE::Action::Type::Generic);
96  PROCESS_VAL(ROSEE::Action::Type::Composed);
97  PROCESS_VAL(ROSEE::Action::Type::Timed);
98  PROCESS_VAL(ROSEE::Action::Type::None);
99  }
100 #undef PROCESS_VAL
101 
102  return out << s;
103 }
#define PROCESS_VAL(p)