17 #ifndef ROSSERVICEHANDLER_H 18 #define ROSSERVICEHANDLER_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> 63 bool selectablePairInfoCallback ( rosee_msg::SelectablePairInfo::Request& request, rosee_msg::SelectablePairInfo::Response& response);
66 rosee_msg::GraspingActionsAvailable::Response& response);
85 rosee_msg::GraspingPrimitiveAggregatedAvailable::Request& request,
86 rosee_msg::GraspingPrimitiveAggregatedAvailable::Response& response);
94 rosee_msg::HandInfo::Request& request,
95 rosee_msg::HandInfo::Response& response);
98 rosee_msg::NewGenericGraspingActionSrv::Request& request,
99 rosee_msg::NewGenericGraspingActionSrv::Response& response);
104 #endif // ROSSERVICEHANDLER_H bool graspingActionsCallback(rosee_msg::GraspingActionsAvailable::Request &request, rosee_msg::GraspingActionsAvailable::Response &response)
bool handInfoCallback(rosee_msg::HandInfo::Request &request, rosee_msg::HandInfo::Response &response)
RosServiceHandler(ros::NodeHandle *nh, ROSEE::MapActionHandler::Ptr, std::string path2saveYamlGeneric)
Default constructor.
bool newGraspingActionCallback(rosee_msg::NewGenericGraspingActionSrv::Request &request, rosee_msg::NewGenericGraspingActionSrv::Response &response)
ros::ServiceServer _serverNewGraspingAction
MapActionHandler::Ptr _mapActionHandler
std::shared_ptr< ActionGeneric > Ptr
void fillCommonInfoGraspingActionMsg(ROSEE::Action::Ptr action, rosee_msg::GraspingAction *msg)
Internal function called by each of the fillGraspingActionMsg, it fills the GraspingAction message wi...
std::shared_ptr< ActionPrimitive > Ptr
std::string _path2saveYamlGeneric
rosee_msg::HandInfo::Response handInfoResponse
std::shared_ptr< MapActionHandler > Ptr
rosee_msg::GraspingAction fillGraspingActionMsg(ROSEE::ActionPrimitive::Ptr primitive)
std::shared_ptr< ActionTimed > Ptr
std::shared_ptr< Action > Ptr
bool init(unsigned int nFinger)
ros::ServiceServer _serverPrimitiveAggregated
rosee_msg::GraspingPrimitiveAggregated fillPrimitiveAggregatedMsg(ROSEE::MapActionHandler::ActionPrimitiveMap primitiveMap)
ros::ServiceServer _serverHandInfo
ros::ServiceServer _server_selectablePairInfo
std::map< std::set< std::string >, ROSEE::ActionPrimitive::Ptr > ActionPrimitiveMap
ros::ServiceServer _serverGraspingActions
bool primitiveAggregatedCallback(rosee_msg::GraspingPrimitiveAggregatedAvailable::Request &request, rosee_msg::GraspingPrimitiveAggregatedAvailable::Response &response)
bool selectablePairInfoCallback(rosee_msg::SelectablePairInfo::Request &request, rosee_msg::SelectablePairInfo::Response &response)