ActionPinchTight.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 IIT-HHCM
3  * Author: Davide Torielli
4  * email: davide.torielli@iit.it
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 #ifndef __ROSEE_ACTIONPINCHTIGHT_H
20 #define __ROSEE_ACTIONPINCHTIGHT_H
21 
24 #include <yaml-cpp/yaml.h>
25 #include <iostream>
26 
27 namespace ROSEE {
28 
41 {
42 
43 public:
44 
45  typedef std::map < std::pair<std::string, std::string>, ActionPinchTight > Map;
46 
47 
49  typedef std::pair <JointPos, collision_detection::Contact> StateWithContact;
50 
53  ActionPinchTight (std::pair <std::string, std::string>, JointPos, collision_detection::Contact );
54  ActionPinchTight (std::string finger1, std::string finger2, JointPos, collision_detection::Contact );
55 
56  JointPos getJointPos () const override;
57  JointPos getJointPos (unsigned int index) const;
58 
59  std::vector < ROSEE::JointPos > getAllJointPos () const override;
60 
65  std::vector < ROSEE::ActionPinchTight::StateWithContact > getActionStates() const;
66 
78 
81  void print () const override;
82  void emitYaml ( YAML::Emitter& ) const override;
83  bool fillFromYaml( YAML::const_iterator yamlIt ) override;
84 
85 private:
86 
88  bool emitYamlForContact ( collision_detection::Contact, YAML::Emitter& ) const;
89 
90 
99  struct depthComp {
100  bool operator() (const StateWithContact& a, const StateWithContact& b) const
101  {return (std::abs(a.second.depth) > std::abs(b.second.depth) );}
102  };
103 
109  std::set < StateWithContact, depthComp > actionStates;
110 
111 };
112 
113 }
114 
115 #endif // __ROSEE_ACTIONPINCHTIGHT_H
ROSEE::ActionPinchTight::getAllJointPos
std::vector< ROSEE::JointPos > getAllJointPos() const override
Return all the joint position stored. If the concrete (derived from Action) has only one joint positi...
Definition: ActionPinchTight.cpp:60
ROSEE::ActionPinchTight::depthComp
struct to put in order the actionStates. The first elements are the ones with greater depth @FIX,...
Definition: ActionPinchTight.h:99
ROSEE::ActionPinchTight::emitYaml
void emitYaml(YAML::Emitter &) const override
Function to fill the argument passed with info about the action. Pure virtual because each derived cl...
Definition: ActionPinchTight.cpp:156
ROSEE
Definition: EEInterface.h:30
ActionPinchGeneric.h
ROSEE::ActionPinchGeneric
A base virtual class for the PinchTight and PinchLoose classes. It includes member and method that ar...
Definition: ActionPinchGeneric.h:31
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
collision_detection::Contact
ROSEE::ActionPinchTight::getActionStates
std::vector< ROSEE::ActionPinchTight::StateWithContact > getActionStates() const
Specific get for the ActionPinchTight to return the state with contact info.
Definition: ActionPinchTight.cpp:73
a
list a
ROSEE::ActionPinchTight::Map
std::map< std::pair< std::string, std::string >, ActionPinchTight > Map
Definition: ActionPinchTight.h:45
ROSEE::ActionPinchTight::fillFromYaml
bool fillFromYaml(YAML::const_iterator yamlIt) override
function to fill members of the Action with infos taken from yaml files
Definition: ActionPinchTight.cpp:197
ROSEE::ActionPinchTight::getJointPos
JointPos getJointPos() const override
Get the position related to this action. Pure Virtual function: the derived class store this info dif...
Definition: ActionPinchTight.cpp:47
ROSEE::ActionPinchTight::actionStates
std::set< StateWithContact, depthComp > actionStates
For each pair, we want a set of action because we want to store (in general) more possible way to do ...
Definition: ActionPinchTight.h:109
ROSEE::ActionPinchTight::emitYamlForContact
bool emitYamlForContact(collision_detection::Contact, YAML::Emitter &) const
Definition: ActionPinchTight.cpp:294
ROSEE::ActionPinchTight::print
void print() const override
Definition: ActionPinchTight.cpp:115
ROSEE::ActionPinchTight::depthComp::operator()
bool operator()(const StateWithContact &a, const StateWithContact &b) const
Definition: ActionPinchTight.h:100
planning_scene.h
ROSEE::ActionPinchTight::ActionPinchTight
ActionPinchTight()
Definition: ActionPinchTight.cpp:21
ROSEE::ActionPinchTight::StateWithContact
std::pair< JointPos, collision_detection::Contact > StateWithContact
A pair to "link" the JointPos with infos about the collision among the two tips.
Definition: ActionPinchTight.h:49
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
ROSEE::ActionPinchTight::insertActionState
bool insertActionState(JointPos, collision_detection::Contact)
function to insert a single action in the actionStates set of possible action. If the action is not s...
Definition: ActionPinchTight.cpp:86
ROSEE::ActionPrimitive::maxStoredActionStates
const unsigned int maxStoredActionStates
Definition: ActionPrimitive.h:95


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