Go to the documentation of this file.
19 #ifndef __ROSEE_ACTIONPINCHLOOSE_H
20 #define __ROSEE_ACTIONPINCHLOOSE_H
25 #include <yaml-cpp/yaml.h>
69 std::vector < ROSEE::ActionPinchLoose::StateWithDistance >
getActionStates()
const;
86 void print ()
const override;
87 void emitYaml ( YAML::Emitter&)
const override;
88 bool fillFromYaml( YAML::const_iterator yamlIt )
override;
97 {
return (std::abs(
a.second) < std::abs(b.second) );}
111 #endif // __ROSEE_ACTIONPINCHLOOSE_H
bool insertActionState(JointPos, double distance)
function to insert a single action in the actionStates set of possible action. If the action is not s...
bool operator()(const StateWithDistance &a, const StateWithDistance &b) const
A base virtual class for the PinchTight and PinchLoose classes. It includes member and method that ar...
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 ...
void emitYaml(YAML::Emitter &) const override
Function to fill the argument passed with info about the action. Pure virtual because each derived cl...
std::vector< ROSEE::ActionPinchLoose::StateWithDistance > getActionStates() const
Specific get for this action to return the state with distance info.
std::map< std::pair< std::string, std::string >, ActionPinchLoose > Map
bool fillFromYaml(YAML::const_iterator yamlIt) override
function to fill members of the Action with infos taken from yaml files
void print() const override
Overridable functions, if we want to make them more action-specific.
JointPos getJointPos() const override
Get the position related to this action. Pure Virtual function: the derived class store this info dif...
The action of pinch with two tips. The two tips must not collide ever (otherwise we have a TightPinch...
std::pair< JointPos, double > StateWithDistance
A pair to "link" the JointPos with the optional info 'distance'.
std::vector< ROSEE::JointPos > getAllJointPos() const override
Return all the joint position stored. If the concrete (derived from Action) has only one joint positi...
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,...
struct to put in order the actionStates set. The first elements are the ones with lesser distance
const unsigned int maxStoredActionStates
end-effector
Author(s): Luca Muratore
, Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26