RosServiceHandler.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020 <copyright holder> <email>
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef ROSSERVICEHANDLER_H
18 #define ROSSERVICEHANDLER_H
19 
20 #include <ros/ros.h>
22 #include <rosee_msg/GraspingPrimitiveAggregated.h>
23 #include <rosee_msg/GraspingPrimitiveAggregatedAvailable.h>
24 #include <rosee_msg/SelectablePairInfo.h>
25 #include <rosee_msg/GraspingActionsAvailable.h>
26 #include <rosee_msg/GraspingAction.h>
27 #include <rosee_msg/MotorPosition.h>
28 #include <rosee_msg/HandInfo.h>
29 #include <rosee_msg/NewGenericGraspingAction.h>
30 #include <rosee_msg/NewGenericGraspingActionSrv.h>
31 
32 
33 namespace ROSEE {
38 {
39 public:
43  RosServiceHandler(ros::NodeHandle *nh, ROSEE::MapActionHandler::Ptr, std::string path2saveYamlGeneric);
44  bool init(unsigned int nFinger);
45 
46  //this response is filled by UROSEE in the initialization
47  rosee_msg::HandInfo::Response handInfoResponse;
48 private:
49 
51  std::string _path2saveYamlGeneric;
57 
59 
60 
61  unsigned int nFinger;
62 
63  bool selectablePairInfoCallback ( rosee_msg::SelectablePairInfo::Request& request, rosee_msg::SelectablePairInfo::Response& response);
64 
65  bool graspingActionsCallback(rosee_msg::GraspingActionsAvailable::Request& request,
66  rosee_msg::GraspingActionsAvailable::Response& response);
67 
68  rosee_msg::GraspingAction fillGraspingActionMsg(ROSEE::ActionPrimitive::Ptr primitive);
69  rosee_msg::GraspingAction fillGraspingActionMsg(ROSEE::ActionGeneric::Ptr generic);
70  rosee_msg::GraspingAction fillGraspingActionMsg(ROSEE::ActionTimed::Ptr timed);
71 
81  void fillCommonInfoGraspingActionMsg(ROSEE::Action::Ptr action, rosee_msg::GraspingAction* msg);
82 
83 
85  rosee_msg::GraspingPrimitiveAggregatedAvailable::Request& request,
86  rosee_msg::GraspingPrimitiveAggregatedAvailable::Response& response);
87 
88  rosee_msg::GraspingPrimitiveAggregated fillPrimitiveAggregatedMsg(
90  rosee_msg::GraspingPrimitiveAggregated fillPrimitiveAggregatedMsg(
91  ROSEE::ActionPrimitive::Ptr primitive);
92 
93  bool handInfoCallback(
94  rosee_msg::HandInfo::Request& request,
95  rosee_msg::HandInfo::Response& response);
96 
98  rosee_msg::NewGenericGraspingActionSrv::Request& request,
99  rosee_msg::NewGenericGraspingActionSrv::Response& response);
100 };
101 
102 } //end namespace
103 
104 #endif // ROSSERVICEHANDLER_H
ROSEE::RosServiceHandler::_mapActionHandler
MapActionHandler::Ptr _mapActionHandler
Definition: RosServiceHandler.h:50
ROSEE::ActionPrimitive::Ptr
std::shared_ptr< ActionPrimitive > Ptr
Definition: ActionPrimitive.h:53
ROSEE::RosServiceHandler::fillCommonInfoGraspingActionMsg
void fillCommonInfoGraspingActionMsg(ROSEE::Action::Ptr action, rosee_msg::GraspingAction *msg)
Internal function called by each of the fillGraspingActionMsg, it fills the GraspingAction message wi...
Definition: RosServiceHandler.cpp:221
MapActionHandler.h
ros.h
ROSEE::RosServiceHandler::_serverPrimitiveAggregated
ros::ServiceServer _serverPrimitiveAggregated
Definition: RosServiceHandler.h:53
ROSEE
Definition: EEInterface.h:30
ROSEE::RosServiceHandler::init
bool init(unsigned int nFinger)
Definition: RosServiceHandler.cpp:34
ROSEE::RosServiceHandler::_serverGraspingActions
ros::ServiceServer _serverGraspingActions
Definition: RosServiceHandler.h:55
ROSEE::RosServiceHandler::fillPrimitiveAggregatedMsg
rosee_msg::GraspingPrimitiveAggregated fillPrimitiveAggregatedMsg(ROSEE::MapActionHandler::ActionPrimitiveMap primitiveMap)
Definition: RosServiceHandler.cpp:304
ROSEE::RosServiceHandler::fillGraspingActionMsg
rosee_msg::GraspingAction fillGraspingActionMsg(ROSEE::ActionPrimitive::Ptr primitive)
Definition: RosServiceHandler.cpp:163
ROSEE::RosServiceHandler::selectablePairInfoCallback
bool selectablePairInfoCallback(rosee_msg::SelectablePairInfo::Request &request, rosee_msg::SelectablePairInfo::Response &response)
Definition: RosServiceHandler.cpp:337
ROSEE::RosServiceHandler::_server_selectablePairInfo
ros::ServiceServer _server_selectablePairInfo
Definition: RosServiceHandler.h:54
ros::ServiceServer
ROSEE::RosServiceHandler
Definition: RosServiceHandler.h:37
ROSEE::RosServiceHandler::newGraspingActionCallback
bool newGraspingActionCallback(rosee_msg::NewGenericGraspingActionSrv::Request &request, rosee_msg::NewGenericGraspingActionSrv::Response &response)
Definition: RosServiceHandler.cpp:397
ROSEE::RosServiceHandler::_path2saveYamlGeneric
std::string _path2saveYamlGeneric
Definition: RosServiceHandler.h:51
ROSEE::MapActionHandler::Ptr
std::shared_ptr< MapActionHandler > Ptr
Definition: MapActionHandler.h:43
ROSEE::RosServiceHandler::handInfoCallback
bool handInfoCallback(rosee_msg::HandInfo::Request &request, rosee_msg::HandInfo::Response &response)
Definition: RosServiceHandler.cpp:370
ROSEE::RosServiceHandler::primitiveAggregatedCallback
bool primitiveAggregatedCallback(rosee_msg::GraspingPrimitiveAggregatedAvailable::Request &request, rosee_msg::GraspingPrimitiveAggregatedAvailable::Response &response)
Definition: RosServiceHandler.cpp:251
ROSEE::RosServiceHandler::nFinger
unsigned int nFinger
Definition: RosServiceHandler.h:61
ROSEE::ActionTimed::Ptr
std::shared_ptr< ActionTimed > Ptr
Definition: ActionTimed.h:42
ROSEE::RosServiceHandler::_serverNewGraspingAction
ros::ServiceServer _serverNewGraspingAction
Definition: RosServiceHandler.h:56
ROSEE::Action::Ptr
std::shared_ptr< Action > Ptr
Definition: Action.h:75
ROSEE::MapActionHandler::ActionPrimitiveMap
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > ActionPrimitiveMap
Definition: MapActionHandler.h:47
ROSEE::RosServiceHandler::RosServiceHandler
RosServiceHandler(ros::NodeHandle *nh, ROSEE::MapActionHandler::Ptr, std::string path2saveYamlGeneric)
Definition: RosServiceHandler.cpp:19
ROSEE::ActionGeneric::Ptr
std::shared_ptr< ActionGeneric > Ptr
Definition: ActionGeneric.h:35
ROSEE::RosServiceHandler::graspingActionsCallback
bool graspingActionsCallback(rosee_msg::GraspingActionsAvailable::Request &request, rosee_msg::GraspingActionsAvailable::Response &response)
Definition: RosServiceHandler.cpp:65
ROSEE::RosServiceHandler::_serverHandInfo
ros::ServiceServer _serverHandInfo
Definition: RosServiceHandler.h:58
ROSEE::RosServiceHandler::_nh
ros::NodeHandle * _nh
Definition: RosServiceHandler.h:52
ROSEE::RosServiceHandler::handInfoResponse
rosee_msg::HandInfo::Response handInfoResponse
Definition: RosServiceHandler.h:47
ros::NodeHandle


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