ActionPinchLoose.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_ACTIONPINCHLOOSE_H
20 #define __ROSEE_ACTIONPINCHLOOSE_H
21 
25 #include <yaml-cpp/yaml.h>
26 #include <iostream>
27 
28 namespace ROSEE {
29 
44 {
45 
46 public:
47 
48  typedef std::map < std::pair<std::string, std::string>, ActionPinchLoose > Map;
49 
53  typedef std::pair <JointPos, double> StateWithDistance;
54 
56  ActionPinchLoose ( unsigned int maxStoredActionStates );
57  ActionPinchLoose ( std::string tip1, std::string tip2);
58  ActionPinchLoose ( std::pair <std::string, std::string>, JointPos, double distance );
59 
60  JointPos getJointPos () const override;
61  JointPos getJointPos (unsigned int index) const;
62 
63  std::vector < ROSEE::JointPos > getAllJointPos () const override;
64 
69  std::vector < ROSEE::ActionPinchLoose::StateWithDistance > getActionStates() const;
70 
71 
82  bool insertActionState (JointPos, double distance);
83 
84  /* For the pinch, we override these function to print, emit and parse the optional info Contact,
85  which is specific of the pinch */
86  void print () const override;
87  void emitYaml ( YAML::Emitter&) const override;
88  bool fillFromYaml( YAML::const_iterator yamlIt ) override;
89 
90 private:
91 
95  struct distComp {
96  bool operator() (const StateWithDistance& a, const StateWithDistance& b) const
97  {return (std::abs(a.second) < std::abs(b.second) );}
98  };
99 
105  std::set < StateWithDistance, distComp > actionStates;
106 
107 };
108 
109 }
110 
111 #endif // __ROSEE_ACTIONPINCHLOOSE_H
ROSEE::ActionPinchLoose::insertActionState
bool insertActionState(JointPos, double distance)
function to insert a single action in the actionStates set of possible action. If the action is not s...
Definition: ActionPinchLoose.cpp:82
ROSEE::ActionPinchLoose::distComp::operator()
bool operator()(const StateWithDistance &a, const StateWithDistance &b) const
Definition: ActionPinchLoose.h:96
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::ActionPinchLoose::actionStates
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 ...
Definition: ActionPinchLoose.h:105
ActionPrimitive.h
ROSEE::ActionPinchLoose::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: ActionPinchLoose.cpp:140
ROSEE::ActionPinchLoose::getActionStates
std::vector< ROSEE::ActionPinchLoose::StateWithDistance > getActionStates() const
Specific get for this action to return the state with distance info.
Definition: ActionPinchLoose.cpp:44
a
list a
ROSEE::ActionPinchLoose::Map
std::map< std::pair< std::string, std::string >, ActionPinchLoose > Map
Definition: ActionPinchLoose.h:48
ROSEE::ActionPinchLoose::fillFromYaml
bool fillFromYaml(YAML::const_iterator yamlIt) override
function to fill members of the Action with infos taken from yaml files
Definition: ActionPinchLoose.cpp:182
ROSEE::ActionPinchLoose::print
void print() const override
Overridable functions, if we want to make them more action-specific.
Definition: ActionPinchLoose.cpp:106
ROSEE::ActionPinchLoose::ActionPinchLoose
ActionPinchLoose()
Definition: ActionPinchLoose.cpp:21
planning_scene.h
ROSEE::ActionPinchLoose::getJointPos
JointPos getJointPos() const override
Get the position related to this action. Pure Virtual function: the derived class store this info dif...
Definition: ActionPinchLoose.cpp:56
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::ActionPinchLoose::StateWithDistance
std::pair< JointPos, double > StateWithDistance
A pair to "link" the JointPos with the optional info 'distance'.
Definition: ActionPinchLoose.h:53
ROSEE::ActionPinchLoose::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: ActionPinchLoose.cpp:70
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::ActionPinchLoose::distComp
struct to put in order the actionStates set. The first elements are the ones with lesser distance
Definition: ActionPinchLoose.h:95
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