UniversalRosEndEffectorExecutor.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 IIT-HHCM
3  * Author: Luca Muratore
4  * email: luca.muratore@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  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16 */
17 
18 #ifndef __ROSEE_UNIVERSAL_ROS_END_EFFECTOR_EXECUTOR_
19 #define __ROSEE_UNIVERSAL_ROS_END_EFFECTOR_EXECUTOR_
20 
21 #include <memory>
22 #include <string>
23 
24 #include <ros/console.h>
26 
27 #include <sensor_msgs/JointState.h>
28 
29 #include <end_effector/Parser.h>
31 #include <end_effector/Utils.h>
36 
39 #include <rosee_msg/HandInfo.h>
40 
41 namespace ROSEE
42 {
43 
49 {
50 
51 public:
52 
53  typedef std::shared_ptr<UniversalRosEndEffectorExecutor> Ptr;
54  typedef std::shared_ptr<const UniversalRosEndEffectorExecutor> ConstPtr;
55 
56  UniversalRosEndEffectorExecutor ( std::string ns = "" );
58 
59  void spin();
60 
61  void timer_callback ( const ros::TimerEvent& timer_ev );
62 
63 private:
64 
66  bool init_qref_filter();
67  void init_joint_state_sub();
69 
71 
72  bool updateGoal(); //the "new" pinch/grasp callback (now used for all actions)
73  bool readOptionalCommands(std::vector<std::string> motors_names, std::vector<double> motors_commands);
74  bool updateRefGoal(double percentage = 1.0);
75  double sendFeedbackGoal(std::string currentAction = "");
76  bool update_send_timed();
77 
80 
81  double _time, _period, _rate;
82 
84 
86  sensor_msgs::JointState _mr_msg;
87  int _motors_num = 0;
88  int _seq_id = 0;
89 
92  void joint_state_clbk(const sensor_msgs::JointStateConstPtr& msg);
93 
94  std::vector<std::string> _motors_names;
95 
96  std::string folderForActions;
97 
98  Eigen::VectorXd _qref, _qref_filtered, _qref_optional;
99 
101 
102  // grasping primitives maps
103  // TODO still needed? now we have the handler that store them...
104  std::map<std::set<std::string>, ROSEE::ActionPrimitive::Ptr> _pinchParsedMap;
105  std::map<std::set<std::string>, ROSEE::ActionPrimitive::Ptr> _pinchLooseParsedMap;
106  std::map<std::set<std::string>, ROSEE::ActionPrimitive::Ptr> _trigParsedMap;
107  std::map<std::set<std::string>, ROSEE::ActionPrimitive::Ptr> _tipFlexParsedMap;
108  std::map<std::set<std::string>, ROSEE::ActionPrimitive::Ptr> _fingFlexParsedMap;
109 
110  std::shared_ptr<ROSEE::ActionGeneric> _graspParsed;
111 
113 
114  std::shared_ptr <RosServiceHandler> _ros_service_handler;
115  std::shared_ptr <RosActionServer> _ros_action_server;
116 
120 
122  std::shared_ptr<ROSEE::ActionTimed> timedAction;
123  unsigned int timed_index;
124  ROSEE::Utils::Timer<> timer; //for time margins of timed action
125  double msToWait;
126 
127 };
128 
129 } //namespace
130 
131 #endif //__ROSEE_UNIVERSAL_ROS_END_EFFECTOR_EXECUTOR_
ROSEE::UniversalRosEndEffectorExecutor::msToWait
double msToWait
Definition: UniversalRosEndEffectorExecutor.h:125
ROSEE::UniversalRosEndEffectorExecutor::_motor_position_goal
ROSEE::JointPos _motor_position_goal
Definition: UniversalRosEndEffectorExecutor.h:118
ROSEE::UniversalRosEndEffectorExecutor::init_grasping_primitive
bool init_grasping_primitive()
Definition: UniversalRosEndEffectorExecutor.cpp:115
ROSEE::UniversalRosEndEffectorExecutor
Class representing the ROS executor implementing the unviversal ROS EE concept.
Definition: UniversalRosEndEffectorExecutor.h:48
ROSEE::UniversalRosEndEffectorExecutor::_ee
ROSEE::EEInterface::Ptr _ee
Definition: UniversalRosEndEffectorExecutor.h:83
ROSEE::UniversalRosEndEffectorExecutor::_fingFlexParsedMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > _fingFlexParsedMap
Definition: UniversalRosEndEffectorExecutor.h:108
ROSEE::UniversalRosEndEffectorExecutor::_qref
Eigen::VectorXd _qref
Definition: UniversalRosEndEffectorExecutor.h:98
ros::Publisher
Parser.h
ROSEE::ActionPrimitive::Ptr
std::shared_ptr< ActionPrimitive > Ptr
Definition: ActionPrimitive.h:53
ROSEE::UniversalRosEndEffectorExecutor::_qref_filtered
Eigen::VectorXd _qref_filtered
Definition: UniversalRosEndEffectorExecutor.h:98
MapActionHandler.h
ROSEE::UniversalRosEndEffectorExecutor::init_qref_filter
bool init_qref_filter()
Definition: UniversalRosEndEffectorExecutor.cpp:91
ROSEE
Definition: EEInterface.h:30
YamlWorker.h
ROSEE::JointsInvolvedCount
std::map< std::string, unsigned int > JointsInvolvedCount
The map to describe, how many times a joint is set by the action. An ActionPrimitive and an ActionCom...
Definition: Action.h:63
ROSEE::UniversalRosEndEffectorExecutor::_graspParsed
std::shared_ptr< ROSEE::ActionGeneric > _graspParsed
Definition: UniversalRosEndEffectorExecutor.h:110
ROSEE::UniversalRosEndEffectorExecutor::UniversalRosEndEffectorExecutor
UniversalRosEndEffectorExecutor(std::string ns="")
Definition: UniversalRosEndEffectorExecutor.cpp:21
ROSEE::UniversalRosEndEffectorExecutor::mapActionHandlerPtr
MapActionHandler::Ptr mapActionHandlerPtr
Definition: UniversalRosEndEffectorExecutor.h:112
ROSEE::UniversalRosEndEffectorExecutor::spin
void spin()
Definition: UniversalRosEndEffectorExecutor.cpp:499
simple_action_server.h
ROSEE::UniversalRosEndEffectorExecutor::~UniversalRosEndEffectorExecutor
virtual ~UniversalRosEndEffectorExecutor()
Definition: UniversalRosEndEffectorExecutor.cpp:510
ROSEE::UniversalRosEndEffectorExecutor::publish_motor_reference
bool publish_motor_reference()
Definition: UniversalRosEndEffectorExecutor.cpp:412
ActionPrimitive.h
ROSEE::UniversalRosEndEffectorExecutor::_ros_action_server
std::shared_ptr< RosActionServer > _ros_action_server
Definition: UniversalRosEndEffectorExecutor.h:115
ROSEE::UniversalRosEndEffectorExecutor::ConstPtr
std::shared_ptr< const UniversalRosEndEffectorExecutor > ConstPtr
Definition: UniversalRosEndEffectorExecutor.h:54
EEInterface.h
ActionComposed.h
ROSEE::UniversalRosEndEffectorExecutor::update_send_timed
bool update_send_timed()
console.h
Utils.h
ROSEE::UniversalRosEndEffectorExecutor::_tipFlexParsedMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > _tipFlexParsedMap
Definition: UniversalRosEndEffectorExecutor.h:107
ROSEE::UniversalRosEndEffectorExecutor::_period
double _period
Definition: UniversalRosEndEffectorExecutor.h:81
ROSEE::UniversalRosEndEffectorExecutor::_motor_involved_mask
ROSEE::JointsInvolvedCount _motor_involved_mask
Definition: UniversalRosEndEffectorExecutor.h:117
ROSEE::Utils::SecondOrderFilter< Eigen::VectorXd >
ROSEE::UniversalRosEndEffectorExecutor::_ros_service_handler
std::shared_ptr< RosServiceHandler > _ros_service_handler
Definition: UniversalRosEndEffectorExecutor.h:114
ROSEE::UniversalRosEndEffectorExecutor::_pinchParsedMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > _pinchParsedMap
Definition: UniversalRosEndEffectorExecutor.h:104
ROSEE::UniversalRosEndEffectorExecutor::sendFeedbackGoal
double sendFeedbackGoal(std::string currentAction="")
Definition: UniversalRosEndEffectorExecutor.cpp:373
ROSEE::UniversalRosEndEffectorExecutor::updateRefGoal
bool updateRefGoal(double percentage=1.0)
Definition: UniversalRosEndEffectorExecutor.cpp:328
ROSEE::UniversalRosEndEffectorExecutor::joint_state_clbk
void joint_state_clbk(const sensor_msgs::JointStateConstPtr &msg)
Definition: UniversalRosEndEffectorExecutor.cpp:180
ROSEE::UniversalRosEndEffectorExecutor::Ptr
std::shared_ptr< UniversalRosEndEffectorExecutor > Ptr
Definition: UniversalRosEndEffectorExecutor.h:53
ROSEE::UniversalRosEndEffectorExecutor::_joint_state_sub
ros::Subscriber _joint_state_sub
Definition: UniversalRosEndEffectorExecutor.h:91
ROSEE::MapActionHandler::Ptr
std::shared_ptr< MapActionHandler > Ptr
Definition: MapActionHandler.h:43
ROSEE::UniversalRosEndEffectorExecutor::normGoalFromInitialPos
double normGoalFromInitialPos
Definition: UniversalRosEndEffectorExecutor.h:119
ros::TimerEvent
ROSEE::UniversalRosEndEffectorExecutor::_motors_names
std::vector< std::string > _motors_names
Definition: UniversalRosEndEffectorExecutor.h:94
ROSEE::UniversalRosEndEffectorExecutor::_filt_q
ROSEE::Utils::SecondOrderFilter< Eigen::VectorXd > _filt_q
Definition: UniversalRosEndEffectorExecutor.h:100
ROSEE::UniversalRosEndEffectorExecutor::timed_index
unsigned int timed_index
Definition: UniversalRosEndEffectorExecutor.h:123
ROSEE::UniversalRosEndEffectorExecutor::updateGoal
bool updateGoal()
Definition: UniversalRosEndEffectorExecutor.cpp:191
ROSEE::UniversalRosEndEffectorExecutor::_joint_actual_pos
ROSEE::JointPos _joint_actual_pos
Definition: UniversalRosEndEffectorExecutor.h:90
ROSEE::UniversalRosEndEffectorExecutor::folderForActions
std::string folderForActions
Definition: UniversalRosEndEffectorExecutor.h:96
RosActionServer.h
ROSEE::UniversalRosEndEffectorExecutor::_loop_timer
ros::Timer _loop_timer
Definition: UniversalRosEndEffectorExecutor.h:79
ROSEE::UniversalRosEndEffectorExecutor::_motors_num
int _motors_num
Definition: UniversalRosEndEffectorExecutor.h:87
ROSEE::UniversalRosEndEffectorExecutor::_pinchLooseParsedMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > _pinchLooseParsedMap
Definition: UniversalRosEndEffectorExecutor.h:105
ROSEE::UniversalRosEndEffectorExecutor::readOptionalCommands
bool readOptionalCommands(std::vector< std::string > motors_names, std::vector< double > motors_commands)
Definition: UniversalRosEndEffectorExecutor.cpp:292
ROSEE::UniversalRosEndEffectorExecutor::timer_callback
void timer_callback(const ros::TimerEvent &timer_ev)
Definition: UniversalRosEndEffectorExecutor.cpp:434
ROSEE::UniversalRosEndEffectorExecutor::init_joint_state_sub
void init_joint_state_sub()
Definition: UniversalRosEndEffectorExecutor.cpp:169
ROSEE::UniversalRosEndEffectorExecutor::_mr_msg
sensor_msgs::JointState _mr_msg
Definition: UniversalRosEndEffectorExecutor.h:86
ROSEE::UniversalRosEndEffectorExecutor::_motor_reference_pub
ros::Publisher _motor_reference_pub
Definition: UniversalRosEndEffectorExecutor.h:85
ROSEE::UniversalRosEndEffectorExecutor::timer
ROSEE::Utils::Timer timer
Definition: UniversalRosEndEffectorExecutor.h:124
ROSEE::EEInterface::Ptr
std::shared_ptr< EEInterface > Ptr
Definition: EEInterface.h:40
ROSEE::UniversalRosEndEffectorExecutor::timedAction
std::shared_ptr< ROSEE::ActionTimed > timedAction
Definition: UniversalRosEndEffectorExecutor.h:122
ROSEE::UniversalRosEndEffectorExecutor::_trigParsedMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > _trigParsedMap
Definition: UniversalRosEndEffectorExecutor.h:106
ROSEE::UniversalRosEndEffectorExecutor::init_motor_reference_pub
bool init_motor_reference_pub()
Definition: UniversalRosEndEffectorExecutor.cpp:72
ROSEE::UniversalRosEndEffectorExecutor::_seq_id
int _seq_id
Definition: UniversalRosEndEffectorExecutor.h:88
ROSEE::UniversalRosEndEffectorExecutor::timed_requested
bool timed_requested
Definition: UniversalRosEndEffectorExecutor.h:121
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::Utils::Timer
Definition: Utils.h:274
ROSEE::UniversalRosEndEffectorExecutor::_qref_optional
Eigen::VectorXd _qref_optional
Definition: UniversalRosEndEffectorExecutor.h:98
ros::Timer
ROSEE::UniversalRosEndEffectorExecutor::_time
double _time
Definition: UniversalRosEndEffectorExecutor.h:81
ROSEE::UniversalRosEndEffectorExecutor::_rate
double _rate
Definition: UniversalRosEndEffectorExecutor.h:81
ROSEE::UniversalRosEndEffectorExecutor::_nh
ros::NodeHandle _nh
Definition: UniversalRosEndEffectorExecutor.h:78
ros::NodeHandle
ros::Subscriber
RosServiceHandler.h


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