21 if (mapActionHandler ==
nullptr) {
22 ROS_ERROR_STREAM (
"[RosServiceHandler " << __func__ <<
" ] the mapActionHandler in not initialized");
36 this->nFinger = nFinger;
38 std::string graspingActionsSrvName, actionInfoServiceName,
39 selectablePairInfoServiceName, handInfoServiceName, newGraspingActionServiceName;
41 _nh->param<std::string>(
"/rosee/grasping_action_srv_name", graspingActionsSrvName,
"grasping_actions_available");
42 _nh->param<std::string>(
"/rosee/primitive_aggregated_srv_name", actionInfoServiceName,
"primitives_aggregated_available");
43 _nh->param<std::string>(
"/rosee/selectable_finger_pair_info", selectablePairInfoServiceName,
"selectable_finger_pair_info");
44 _nh->param<std::string>(
"/rosee/hand_info", handInfoServiceName,
"hand_info");
45 _nh->param<std::string>(
"/rosee/new_grasping_action_srv_name", newGraspingActionServiceName,
"new_generic_grasping_action");
47 _serverGraspingActions = _nh->advertiseService(graspingActionsSrvName,
50 _serverPrimitiveAggregated = _nh->advertiseService(actionInfoServiceName,
53 _server_selectablePairInfo = _nh->advertiseService(selectablePairInfoServiceName,
56 _serverHandInfo = _nh->advertiseService(handInfoServiceName,
59 _serverNewGraspingAction = _nh->advertiseService(newGraspingActionServiceName,
66 rosee_msg::GraspingActionsAvailable::Request& request,
67 rosee_msg::GraspingActionsAvailable::Response& response) {
69 switch (request.action_type) {
75 if (request.primitive_type == 0) {
77 if (request.action_name.size() == 0 ) {
78 for (
auto primitiveContainers : _mapActionHandler->getAllPrimitiveMaps() ) {
81 for (
auto primitive : primitiveContainers.second) {
82 response.grasping_actions.push_back(fillGraspingActionMsg(primitive.second));
87 if (request.elements_involved.size() == 0) {
89 for (
auto primitive : _mapActionHandler->getPrimitiveMap(request.action_name)) {
90 response.grasping_actions.push_back(fillGraspingActionMsg(primitive.second));
95 auto primitive =_mapActionHandler->getPrimitive(request.action_name, request.elements_involved);
96 response.grasping_actions.push_back(fillGraspingActionMsg(primitive));
102 if (request.elements_involved.size() == 0) {
105 for (
auto primitives : _mapActionHandler->getPrimitiveMap(
108 for (
auto primitive : primitives) {
109 response.grasping_actions.push_back(fillGraspingActionMsg(primitive.second));
115 for (
auto primitive : _mapActionHandler->getPrimitive(
118 response.grasping_actions.push_back(fillGraspingActionMsg(primitive));
129 if (request.action_name.size() == 0) {
130 for (
auto action : _mapActionHandler->getAllGenerics()) {
131 response.grasping_actions.push_back(fillGraspingActionMsg(action.second));
135 response.grasping_actions.push_back(fillGraspingActionMsg(_mapActionHandler->getGeneric(request.action_name)));
141 if (request.action_name.size() == 0) {
142 for (
auto action : _mapActionHandler->getAllTimeds()) {
143 response.grasping_actions.push_back(fillGraspingActionMsg(action.second));
147 response.grasping_actions.push_back(fillGraspingActionMsg(_mapActionHandler->getTimed(request.action_name)));
153 ROS_ERROR_STREAM (
"[RosServiceHandler " << __func__ <<
" ] request.actionType can only be 0(ALL), 1(PRIMITIVE), "
154 <<
"2(GENERIC_and_COMPOSED), or 3(TIMED); I have received " << request.action_type);
165 rosee_msg::GraspingAction primitiveMsg;
167 if (primitive ==
nullptr) {
171 fillCommonInfoGraspingActionMsg(primitive, &primitiveMsg);
173 primitiveMsg.primitive_type = primitive->getPrimitiveType();
175 auto elements = primitive->getKeyElements();
183 rosee_msg::GraspingAction genericActionMsg;
184 if (
generic ==
nullptr) {
185 return genericActionMsg;
188 fillCommonInfoGraspingActionMsg(
generic, &genericActionMsg);
190 genericActionMsg.primitive_type = genericActionMsg.PRIMITIVE_NONE;
193 if ( composedCasted !=
nullptr) {
194 genericActionMsg.inner_actions = composedCasted->getInnerActionsNames();
197 return genericActionMsg;
202 rosee_msg::GraspingAction timedActionMsg;
203 if (timed ==
nullptr) {
204 return timedActionMsg;
207 fillCommonInfoGraspingActionMsg(timed, &timedActionMsg);
209 timedActionMsg.primitive_type = timedActionMsg.PRIMITIVE_NONE;
211 timedActionMsg.inner_actions = timed->getInnerActionsNames();
213 for (
auto innerMargin : timed->getAllActionMargins()){
214 timedActionMsg.before_time_margins.push_back(innerMargin.first);
215 timedActionMsg.after_time_margins.push_back(innerMargin.second);
218 return timedActionMsg;
222 rosee_msg::GraspingAction* graspingMsg) {
224 graspingMsg->action_type = action->getType();
225 graspingMsg->action_name = action->getName();
228 for (
auto motorCount : action->getJointsInvolvedCount()) {
229 motorCountMsg.name.push_back(motorCount.first);
230 motorCountMsg.count.push_back(motorCount.second);
232 graspingMsg->action_motor_count = motorCountMsg;
234 for (
auto motorPosMultiple : action->getAllJointPos()) {
237 rosee_msg::MotorPosition motorPosMsg;
238 for (
auto motorPos : motorPosMultiple) {
239 motorPosMsg.name.push_back(motorPos.first);
240 motorPosMsg.position.push_back(motorPos.second.at(0));
243 graspingMsg->action_motor_positions.push_back(motorPosMsg);
246 for (
auto elementInvolved : action->getFingersInvolved()) {
247 graspingMsg->elements_involved.push_back(elementInvolved);
252 rosee_msg::GraspingPrimitiveAggregatedAvailable::Request& request,
253 rosee_msg::GraspingPrimitiveAggregatedAvailable::Response& response) {
255 if (request.primitive_type == 0) {
257 if (request.action_name.size() == 0 ) {
260 for (
auto primitiveMaps : _mapActionHandler->getAllPrimitiveMaps() ) {
262 response.primitives_aggregated.push_back(fillPrimitiveAggregatedMsg(primitiveMaps.second));
266 if (request.elements_involved.size() == 0) {
268 auto primitiveMap = _mapActionHandler->getPrimitiveMap(request.action_name);
269 response.primitives_aggregated.push_back(fillPrimitiveAggregatedMsg(primitiveMap));
274 auto primitive =_mapActionHandler->getPrimitive(request.action_name, request.elements_involved);
275 response.primitives_aggregated.push_back(fillPrimitiveAggregatedMsg(primitive));
281 if (request.elements_involved.size() == 0) {
284 for (
auto primitiveMap : _mapActionHandler->getPrimitiveMap(
287 response.primitives_aggregated.push_back(fillPrimitiveAggregatedMsg(primitiveMap));
293 for (
auto primitive : _mapActionHandler->getPrimitive(
296 response.primitives_aggregated.push_back(fillPrimitiveAggregatedMsg(primitive));
307 rosee_msg::GraspingPrimitiveAggregated primitiveMsg;
309 primitiveMsg.action_name = primitiveMap.begin()->second->getName();
310 primitiveMsg.primitive_type = primitiveMap.begin()->second->getPrimitiveType();
314 primitiveMsg.max_selectable = primitiveMap.begin()->first.size();
316 primitiveMsg.selectable_names =
325 rosee_msg::GraspingPrimitiveAggregated primitiveMsg;
326 primitiveMsg.action_name = primitive->getName();
327 primitiveMsg.primitive_type = primitive->getPrimitiveType();
329 auto elements = primitive->getKeyElements();
330 primitiveMsg.max_selectable =
elements.size();
338 rosee_msg::SelectablePairInfo::Request& request,
339 rosee_msg::SelectablePairInfo::Response& response) {
341 std::set<std::string> companionFingers;
342 if (request.action_name.compare (
"pinchTight") == 0) {
344 _mapActionHandler->getFingertipsForPinch(request.element_name,
345 ROSEE::ActionPrimitive::Type::PinchTight) ;
347 }
else if (request.action_name.compare (
"pinchLoose") == 0) {
349 _mapActionHandler->getFingertipsForPinch(request.element_name,
350 ROSEE::ActionPrimitive::Type::PinchLoose) ;
354 "a recognizible action name to look for finger companions" );
358 if (companionFingers.size() == 0) {
363 for (
auto fing : companionFingers ) {
364 response.pair_elements.push_back (fing);
371 rosee_msg::HandInfo::Request& request,
372 rosee_msg::HandInfo::Response& response) {
379 _nh->serviceClient<rosee_msg::HandInfo>(
"/EEHalExecutor/hand_info");
380 rosee_msg::HandInfo handInfoMsg;
383 handInfoMsg.request = request;
384 if (handInfoClient.
call(handInfoMsg)) {
398 rosee_msg::NewGenericGraspingActionSrv::Request& request,
399 rosee_msg::NewGenericGraspingActionSrv::Response& response){
404 if (request.newAction.action_name.empty()) {
406 response.error_msg =
"action_name can not be empty";
411 if (request.newAction.action_motor_position.name.size() == 0 ||
412 request.newAction.action_motor_position.position.size() == 0 ||
413 request.newAction.action_motor_position.position.size() != request.newAction.action_motor_position.name.size()) {
415 response.error_msg =
"action_motor_position is empty or badly formed";
421 if (request.newAction.action_motor_count.name.size() != request.newAction.action_motor_count.count.size()) {
423 response.error_msg =
"action_motor_count is badly formed, name and count have different sizes";
432 if (_mapActionHandler->getGeneric(request.newAction.action_name,
false) !=
nullptr) {
434 response.error_msg =
"A generic action with name '" + request.newAction.action_name +
"' already exists";
444 std::set<std::string> elementInvolved;
446 for (
int i = 0; i < request.newAction.action_motor_position.name.size(); i++){
448 std::vector<double> one_dof{request.newAction.action_motor_position.position.at(i)};
449 jp.insert(std::make_pair(request.newAction.action_motor_position.name.at(i),
453 for (
int i = 0; i < request.newAction.action_motor_count.name.size(); i++){
455 jic.insert(std::make_pair(request.newAction.action_motor_count.name.at(i),
456 request.newAction.action_motor_count.count.at(i)));
459 for (
int i = 0; i< request.newAction.elements_involved.size(); i++) {
461 elementInvolved.insert(request.newAction.elements_involved.at(i));
465 try { newAction = std::make_shared<ROSEE::ActionGeneric>(request.newAction.action_name,
472 response.error_msg =
"action_motor_position and action_motor_count have different names element. They must be the same because they refer to actuator of the end-effector";
480 if (! _mapActionHandler->insertSingleGeneric(newAction)){
482 response.error_msg =
"error by mapActionHandler when inserting the new generic action";
488 ROS_INFO_STREAM (
"[RosServiceHandler " << __func__ <<
" ] The new action '"<< newAction->getName() <<
"' is inserted in the system");
491 if (request.emitYaml) {
494 auto path = yamlWorker.
createYamlFile(newAction, _path2saveYamlGeneric);
495 ROS_INFO_STREAM (
"[RosServiceHandler " << __func__ <<
" ] The received new action '"<< newAction->getName() <<
"' has been stored in " << path);