28#include <yarp/os/Time.h>
29#include <yarp/math/Math.h>
30#include <yarp/math/Rand.h>
43bool MotorThread::checkOptions(
const Bottle &options,
const string ¶meter)
46 for (
int i=0; i<options.size(); i++)
48 if(options.get(i).asString()==parameter)
61 extForceThresh=initializer.check(
"external_force_thresh",Value(1e9)).asFloat64();
62 samplingRate=initializer.check(
"subsampling_rate",Value(500.0)).asFloat64();
64 damping=initializer.check(
"damping",Value(1e9)).asFloat64();
65 inertia=initializer.check(
"inertia",Value(1e9)).asFloat64();
76bool MotorThread::storeContext(
const int arm)
80 if (action[arm]!=NULL)
82 ICartesianControl *ctrl=NULL;
83 if (action[arm]->getCartesianIF(ctrl))
87 ctrl->storeContext(&action_context[arm]);
98bool MotorThread::restoreContext(
const int arm)
102 if (action[arm]!=NULL)
104 ICartesianControl *ctrl=NULL;
105 if (action[arm]->getCartesianIF(ctrl))
110 ctrl->restoreContext(action_context[arm]);
121bool MotorThread::deleteContext(
const int arm)
125 if (action[arm]!=NULL)
127 ICartesianControl *ctrl=NULL;
128 if (action[arm]->getCartesianIF(ctrl))
132 ctrl->deleteContext(action_context[arm]);
145 if (action==&action[
LEFT])
146 return storeContext(
LEFT);
147 else if (action==&action[
RIGHT])
148 return storeContext(
RIGHT);
156 if (action==&action[
LEFT])
157 return restoreContext(
LEFT);
158 else if (action==&action[
RIGHT])
159 return restoreContext(
RIGHT);
167 if (action==&action[
LEFT])
168 return deleteContext(
LEFT);
169 else if (action==&action[
RIGHT])
170 return deleteContext(
RIGHT);
176int MotorThread::checkArm(
int arm)
185int MotorThread::checkArm(
int arm, Vector &xd,
const bool applyOffset)
195 xd[0]+=currentKinematicOffset[armInUse][0];
196 xd[1]+=currentKinematicOffset[armInUse][1];
197 xd[2]+=currentKinematicOffset[armInUse][2];
200 return checkArm(arm);
206 InteractionModeEnum mode=(turn_on?VOCAB_IM_COMPLIANT:VOCAB_IM_STIFF);
207 for(
int i=0; i<5; i++)
209 if(action[
LEFT]!=NULL)
210 int_mode_arm[
LEFT]->setInteractionMode(i,mode);
211 if(action[
RIGHT]!=NULL)
212 int_mode_arm[
RIGHT]->setInteractionMode(i,mode);
215 if (int_mode_torso!=NULL)
217 InteractionModeEnum modes[3]={VOCAB_IM_STIFF, VOCAB_IM_STIFF, VOCAB_IM_STIFF};
218 int_mode_torso->setInteractionModes(modes);
221 status_impedance_on=turn_on;
228 if(action[arm]==NULL)
236 for(
int i=0; i<4; i++)
237 done=
done && ctrl_mode_arm[arm]->setControlMode(i,VOCAB_CM_TORQUE);
239 for(
int i=0; i<3; i++)
240 done=
done && int_mode_torso->setInteractionMode(i,VOCAB_IM_COMPLIANT);
262 if (Network::isConnected(disparityPort.getName(),
"/stereoDisparity/rpc"))
265 string tmp=
"[Stereo -> Cartesian]: Disparity";
266 yInfo(
"%s",tmp.c_str());
267 reply.addString(tmp);
272 string tmp=
"[Stereo -> Cartesian]: Homography";
273 yInfo(
"%s",tmp.c_str());
274 reply.addString(tmp);
281 if (neuralNetworkAvailable)
284 string tmp=
"[Stereo -> Cartesian]: Neural Net";
285 yInfo(
"%s",tmp.c_str());
286 reply.addString(tmp);
291 string tmp=
"[Stereo -> Cartesian]: Homography";
292 yInfo(
"%s",tmp.c_str());
293 reply.addString(tmp);
301 string tmp=
"[Stereo -> Cartesian]: Homography";
302 yInfo(
"%s",tmp.c_str());
303 reply.addString(tmp);
309 if(!bKinOffsets.find(
"left").asList()->check(Vocab32::decode(modeS2C)))
311 Bottle &bKinMode=bKinOffsets.find(
"left").asList()->addList();
312 bKinMode.addString(Vocab32::decode(modeS2C));
313 Bottle &bKinVec=bKinMode.addList();
314 for(
int i=0; i<3; i++)
315 bKinVec.addFloat64(0.0);
318 Bottle *bKinLeft=bKinOffsets.find(
"left").asList()->find(Vocab32::decode(modeS2C)).asList();
319 for(
int i=0; i<3; i++)
320 defaultKinematicOffset[
LEFT][i]=bKinLeft->get(i).asFloat64();
323 if(!bKinOffsets.find(
"right").asList()->check(Vocab32::decode(modeS2C)))
325 Bottle &bKinMode=bKinOffsets.find(
"right").asList()->addList();
326 bKinMode.addString(Vocab32::decode(modeS2C));
327 Bottle &bKinVec=bKinMode.addList();
328 for(
int i=0; i<3; i++)
329 bKinVec.addFloat64(0.0);
332 Bottle *bKinRight=bKinOffsets.find(
"right").asList()->find(Vocab32::decode(modeS2C)).asList();
333 for(
int i=0; i<3; i++)
334 defaultKinematicOffset[
RIGHT][i]=bKinRight->get(i).asFloat64();
345 currentKinematicOffset[
LEFT]=defaultKinematicOffset[
LEFT];
346 currentKinematicOffset[
RIGHT]=defaultKinematicOffset[
RIGHT];
349 if(!found && bTarget!=NULL && bTarget->check(
"cartesian") && bTarget->find(
"cartesian").asList()->size()>=3)
351 Bottle *bCartesian=bTarget->find(
"cartesian").asList();
353 for(
int i=0; i<bCartesian->size(); i++)
354 xd.push_back(bCartesian->get(i).asFloat64());
359 if(!found && bTarget!=NULL && bTarget->check(
"name"))
363 if(!found && bTarget!=NULL && bTarget->check(
"stereo"))
365 Bottle *bStereo=bTarget->find(
"stereo").asList();
370 for(
int i=0; i<bStereo->size(); i++)
371 stereo.push_back(bStereo->get(i).asFloat64());
377 if(found && bTarget!=NULL && bTarget->check(
"name"))
391 yWarning(
"System is busy!");
401 ok=stereoToCartesianHomography(stereo,xd);
407 ok=stereoToCartesianDisparity(stereo,xd);
413 ok=stereoToCartesianNetwork(stereo,xd);
422bool MotorThread::loadExplorationPoses(
const string &file_name)
425 optExpl.fromConfigFile(rf.findFile(file_name));
427 if(!optExpl.check(
"torso") ||!optExpl.check(
"hand") ||!optExpl.check(
"head"))
430 Bottle &tmpTorso=optExpl.findGroup(
"torso");
431 for(
int i=1; i<tmpTorso.size(); i++)
433 Bottle *b=tmpTorso.get(i).asList();
435 for(
int j=0; j<b->size(); j++)
436 v[j]=b->get(j).asFloat64();
437 pos_torsoes.push_back(v);
440 Bottle &tmpHand=optExpl.findGroup(
"hand");
441 for(
int i=1; i<tmpHand.size(); i++)
443 Bottle *b=tmpHand.get(i).asList();
445 for(
int j=0; j<b->size(); j++)
446 v[j]=b->get(j).asFloat64();
447 handPoses.push_back(v);
450 Bottle &tmpHead=optExpl.findGroup(
"head");
451 for(
int i=1; i<tmpHead.size(); i++)
453 Bottle *b=tmpHead.get(i).asList();
455 for(
int j=0; j<b->size(); j++)
456 v[j]=b->get(j).asFloat64();
457 headPoses.push_back(v);
464Vector MotorThread::eye2root(
const Vector &
out,
bool forehead)
476 Vector eyePos,eyeOrient;
478 ctrl_gaze->getHeadPose(eyePos,eyeOrient);
480 ctrl_gaze->getLeftEyePose(eyePos,eyeOrient);
482 Matrix
T=axis2dcm(eyeOrient);
483 T.setSubcol(eyePos,0,3);
485 Vector
root=
T*out_hom;
491 if (root[2]<=table_height)
492 root[2]=table_height;
503bool MotorThread::stereoToCartesianHomography(
const Vector &stereo, Vector &xd)
506 if(stereo[2*dominant_eye]==0.0 && stereo[2*dominant_eye+1]==0.0)
508 if(stereo[2*(1-dominant_eye)]==0.0 && stereo[2*(1-dominant_eye)+1]==0.0)
511 eye_in_use=1-dominant_eye;
514 eye_in_use=dominant_eye;
517 px[0]=stereo[2*eye_in_use];
518 px[1]=stereo[2*eye_in_use+1];
520 ctrl_gaze->get3DPointOnPlane(eye_in_use,px,table,xd);
526bool MotorThread::stereoToCartesianDisparity(
const Vector &stereo, Vector &xd)
529 bEye.addFloat64(stereo[0]);
530 bEye.addFloat64(stereo[1]);
535 disparityPort.write(bEye,bX);
537 while(bX.size()==0 || bX.get(2).asFloat64()<0.0 );
539 if(bX.size()!=0 && bX.get(2).asFloat64()>0.0 )
542 xd[0]=bX.get(0).asFloat64();
543 xd[1]=bX.get(1).asFloat64();
544 xd[2]=bX.get(2).asFloat64();
547 xd=eye2root(xd,
false);
553bool MotorThread::stereoToCartesianNetwork(
const Vector &stereo, Vector &xd)
555 if(stereo.size()!=4 || stereo[0]==0.0 || stereo[1]==0.0 || stereo[2]==0.0 || stereo[3]==0.0)
559 enc_head->getEncoders(
h.data());
570 xd=eye2root(net.
predict(in),
true);
576Vector MotorThread::randomDeployOffset()
579 offset[0]=Rand::scalar(-0.01,0.0);
580 offset[1]=Rand::scalar(-0.02,0.02);
587bool MotorThread::loadKinematicOffsets()
589 ifstream kin_fin(rf.findFile(kinematics_file).c_str());
590 if (!kin_fin.is_open())
592 yError(
"Kinematics file not found!");
597 strstr<<kin_fin.rdbuf();
599 bKinOffsets.fromString(strstr.str());
601 if (!bKinOffsets.check(
"table_height"))
603 Bottle &bKinList=bKinOffsets.addList();
604 bKinList.addString(
"table_height");
605 bKinList.addFloat64(-0.1);
608 table_height=bKinOffsets.find(
"table_height").asFloat64();
611 table[3]=-table_height;
614 table_height+=table_height_tolerance;
616 if (!bKinOffsets.check(
"left"))
618 Bottle &bKinList=bKinOffsets.addList();
619 bKinList.addString(
"left");
624 if (!bKinOffsets.check(
"right"))
626 Bottle &bKinList=bKinOffsets.addList();
627 bKinList.addString(
"right");
634 defaultKinematicOffset[
LEFT].resize(3);
635 defaultKinematicOffset[
RIGHT].resize(3);
641bool MotorThread::saveKinematicOffsets()
643 std::filesystem::path fileName(rf.getHomeContextPath()+
"/"+kinematics_file);
644 std::filesystem::create_directories(fileName.parent_path());
645 ofstream kin_fout(fileName);
646 if (!kin_fout.is_open())
648 yError(
"Unable to open file '%s'!",fileName.c_str());
653 kin_fout<<bKinOffsets.toString()<<endl;
660bool MotorThread::getGeneralOptions(Bottle &b)
662 if (Bottle *pB=b.find(
"home_fixation_point").asList())
664 homeFixCartType=
true;
670 homeFixCartType=(v.asString()==
"xyz");
674 homeFix.resize(pB->size()-offs);
675 for (
size_t i=0; i<homeFix.length(); i++)
676 homeFix[i]=pB->get(offs+i).asFloat64();
681 if (Bottle *pB=b.find(
"reach_above_displacement").asList())
683 reachAboveDisp.resize(pB->size());
685 for (
int i=0; i<pB->size(); i++)
686 reachAboveDisp[i]=pB->get(i).asFloat64();
691 if (Bottle *pB=b.find(
"grasp_above_relief").asList())
693 graspAboveRelief.resize(pB->size());
695 for (
int i=0; i<pB->size(); i++)
696 graspAboveRelief[i]=pB->get(i).asFloat64();
701 if (Bottle *pB=b.find(
"push_above_relief").asList())
703 pushAboveRelief.resize(pB->size());
705 for (
int i=0; i<pB->size(); i++)
706 pushAboveRelief[i]=pB->get(i).asFloat64();
711 go_up_distance=b.check(
"go_up",Value(0.1)).asFloat64();
712 table_height_tolerance=b.find(
"table_height_tolerance").asFloat64();
718bool MotorThread::getArmOptions(Bottle &b,
const int &arm)
720 if (Bottle *pB=b.find(
"home_position").asList())
722 homePos[arm].resize(pB->size());
724 for (
int i=0; i<pB->size(); i++)
725 homePos[arm][i]=pB->get(i).asFloat64();
730 if (Bottle *pB=b.find(
"home_orientation").asList())
732 homeOrient[arm].resize(pB->size());
734 for (
int i=0; i<pB->size(); i++)
735 homeOrient[arm][i]=pB->get(i).asFloat64();
740 if (Bottle *pB=b.find(
"reach_side_displacement").asList())
742 reachSideDisp[arm].resize(pB->size());
744 for (
int i=0; i<pB->size(); i++)
745 reachSideDisp[arm][i]=pB->get(i).asFloat64();
750 if (Bottle *pB=b.find(
"reach_above_orientation").asList())
752 reachAboveOrient[arm].resize(pB->size());
754 for (
int i=0; i<pB->size(); i++)
755 reachAboveOrient[arm][i]=pB->get(i).asFloat64();
760 if (Bottle *pB=b.find(
"reach_above_calib_table").asList())
762 reachAboveCata[arm].resize(pB->size());
764 for (
int i=0; i<pB->size(); i++)
765 reachAboveCata[arm][i]=pB->get(i).asFloat64();
770 if (Bottle *pB=b.find(
"reach_side_orientation").asList())
772 reachSideOrient[arm].resize(pB->size());
774 for (
int i=0; i<pB->size(); i++)
775 reachSideOrient[arm][i]=pB->get(i).asFloat64();
780 if (Bottle *pB=b.find(
"deploy_position").asList())
782 deployPos[arm].resize(pB->size());
784 for (
int i=0; i<pB->size(); i++)
785 deployPos[arm][i]=pB->get(i).asFloat64();
790 if (Bottle *pB=b.find(
"deploy_orientation").asList())
792 deployOrient[arm].resize(pB->size());
793 for (
int i=0; i<pB->size(); i++)
794 deployOrient[arm][i]=pB->get(i).asFloat64();
797 deployOrient[arm]=reachAboveOrient[arm];
799 if (Bottle *pB=b.find(
"draw_near_position").asList())
801 drawNearPos[arm].resize(pB->size());
803 for (
int i=0; i<pB->size(); i++)
804 drawNearPos[arm][i]=pB->get(i).asFloat64();
809 if (Bottle *pB=b.find(
"draw_near_orientation").asList())
811 drawNearOrient[arm].resize(pB->size());
813 for (
int i=0; i<pB->size(); i++)
814 drawNearOrient[arm][i]=pB->get(i).asFloat64();
819 if (Bottle *pB=b.find(
"shift_position").asList())
821 shiftPos[arm].resize(pB->size());
823 for (
int i=0; i<pB->size(); i++)
824 shiftPos[arm][i]=pB->get(i).asFloat64();
828 shiftPos[arm].resize(3);
832 if (Bottle *pB=b.find(
"expect_position").asList())
834 expectPos[arm].resize(pB->size());
836 for (
int i=0; i<pB->size(); i++)
837 expectPos[arm][i]=pB->get(i).asFloat64();
842 if (Bottle *pB=b.find(
"expect_orientation").asList())
844 expectOrient[arm].resize(pB->size());
846 for (
int i=0; i<pB->size(); i++)
847 expectOrient[arm][i]=pB->get(i).asFloat64();
852 if (Bottle *pB=b.find(
"tool_take_position").asList())
854 takeToolPos[arm].resize(pB->size());
856 for (
int i=0; i<pB->size(); i++)
857 takeToolPos[arm][i]=pB->get(i).asFloat64();
862 if (Bottle *pB=b.find(
"tool_take_orientation").asList())
864 takeToolOrient[arm].resize(pB->size());
866 for (
int i=0; i<pB->size(); i++)
867 takeToolOrient[arm][i]=pB->get(i).asFloat64();
872 extForceThresh[arm]=b.check(
"external_forces_thresh",Value(0.0)).asFloat64();
874 string modelFile(
"grasp_model_");
875 modelFile+=(arm==
LEFT?
"left":
"right");
877 graspFile[arm]=b.check(
"grasp_model_file",Value(modelFile)).asString();
883void MotorThread::close()
897 delete drv_arm[
LEFT];
900 delete drv_arm[
RIGHT];
903 delete drv_ctrl_gaze;
909 delete action[
RIGHT];
912 disparityPort.interrupt();
913 disparityPort.close();
918 wrenchPort[
LEFT].interrupt();
919 wrenchPort[
RIGHT].interrupt();
920 wrenchPort[
LEFT].close();
921 wrenchPort[
RIGHT].close();
929 Bottle bMotor=rf.findGroup(
"motor");
932 yError(
"Motor part is missing!");
936 string name=rf.find(
"name").asString();
937 string robot=bMotor.check(
"robot",Value(
"icub")).asString();
938 string partUsed=bMotor.check(
"part_used",Value(
"both_arms")).asString();
939 int actionprimitives_layer=bMotor.check(
"actionprimitives_layer",Value(2)).asInt32();
940 setPeriod((
double)bMotor.check(
"thread_period",Value(100)).asInt32()/1000.0);
942 actions_path=bMotor.check(
"actions",Value(
"actions")).asString();
944 double eyesTrajTime=bMotor.check(
"eyes_traj_time",Value(1.0)).asFloat64();
945 double neckTrajTime=bMotor.check(
"neck_traj_time",Value(2.0)).asFloat64();
947 double kp=bMotor.check(
"stereo_kp",Value(0.001)).asFloat64();
948 double ki=bMotor.check(
"stereo_ki",Value(0.001)).asFloat64();
949 double kd=bMotor.check(
"stereo_kd",Value(0.0)).asFloat64();
951 stereo_track=bMotor.check(
"stereo_track",Value(
"on")).asString()==
"on";
952 dominant_eye=(bMotor.check(
"dominant_eye",Value(
"left")).asString()==
"left")?
LEFT:
RIGHT;
954 Bottle *neckPitchRange=bMotor.find(
"neck_pitch_range").asList();
955 Bottle *neckRollRange=bMotor.find(
"neck_roll_range").asList();
958 disparityPort.open(
"/"+name+
"/disparity:io");
959 wbdPort.open(
"/"+name+
"/wbd:rpc");
960 wrenchPort[
LEFT].open(
"/"+name+
"/left/wrench:o");
961 wrenchPort[
RIGHT].open(
"/"+name+
"/right/wrench:o");
964 Property optHead(
"(device remote_controlboard)");
965 Property optLeftArm(
"(device remote_controlboard)");
966 Property optRightArm(
"(device remote_controlboard)");
967 Property optTorso(
"(device remote_controlboard)");
968 Property optctrl_gaze(
"(device gazecontrollerclient)");
970 optHead.put(
"remote",
"/"+robot+
"/head");
971 optHead.put(
"local",
"/"+name+
"/head");
973 optLeftArm.put(
"remote",
"/"+robot+
"/left_arm");
974 optLeftArm.put(
"local",
"/"+name+
"/left_arm");
976 optRightArm.put(
"remote",
"/"+robot+
"/right_arm");
977 optRightArm.put(
"local",
"/"+name+
"/right_arm");
979 optTorso.put(
"remote",
"/"+robot+
"/torso");
980 optTorso.put(
"local",
"/"+name+
"/torso");
982 optctrl_gaze.put(
"remote",
"/iKinGazeCtrl");
983 optctrl_gaze.put(
"local",
"/"+name+
"/gaze");
985 drv_head=
new PolyDriver;
986 drv_torso=
new PolyDriver;
987 drv_ctrl_gaze=
new PolyDriver;
988 if (!drv_head->open(optHead) ||
989 !drv_torso->open(optTorso) ||
990 !drv_ctrl_gaze->open(optctrl_gaze))
997 drv_head->view(enc_head);
998 drv_torso->view(enc_torso);
999 drv_torso->view(pos_torso);
1000 drv_torso->view(vel_torso);
1001 drv_torso->view(ctrl_mode_torso);
1002 drv_torso->view(int_mode_torso);
1003 drv_torso->view(ctrl_impedance_torso);
1005 if(partUsed==
"both_arms" || partUsed==
"left_arm")
1007 drv_arm[
LEFT]=
new PolyDriver;
1008 if(!drv_arm[
LEFT]->open(optLeftArm))
1014 drv_arm[
LEFT]->view(ctrl_mode_arm[
LEFT]);
1015 drv_arm[
LEFT]->view(int_mode_arm[
LEFT]);
1016 drv_arm[
LEFT]->view(ctrl_impedance_arm[
LEFT]);
1017 drv_arm[
LEFT]->view(pos_arm[
LEFT]);
1018 drv_arm[
LEFT]->view(enc_arm[
LEFT]);
1020 Vector vels(16),accs(16);
1021 vels=20.0; accs=6000.0;
1022 pos_arm[
LEFT]->setRefSpeeds(vels.data());
1023 pos_arm[
LEFT]->setRefAccelerations(accs.data());
1026 if(partUsed==
"both_arms" || partUsed==
"right_arm")
1028 drv_arm[
RIGHT]=
new PolyDriver;
1029 if(!drv_arm[
RIGHT]->open(optRightArm))
1037 drv_arm[
RIGHT]->view(ctrl_impedance_arm[
RIGHT]);
1041 Vector vels(16),accs(16);
1042 vels=20.0; accs=6000.0;
1043 pos_arm[
RIGHT]->setRefSpeeds(vels.data());
1044 pos_arm[
RIGHT]->setRefAccelerations(accs.data());
1047 drv_ctrl_gaze->view(ctrl_gaze);
1049 Vector vels(3),accs(3);
1050 vels=5.0; accs=6000.0;
1051 pos_torso->setRefSpeeds(vels.data());
1052 pos_torso->setRefAccelerations(accs.data());
1057 int initial_gaze_context;
1058 ctrl_gaze->storeContext(&initial_gaze_context);
1060 ctrl_gaze->setTrackingMode(
false);
1061 ctrl_gaze->setEyesTrajTime(eyesTrajTime);
1062 ctrl_gaze->setNeckTrajTime(neckTrajTime);
1066 Bottle &bKp=stereoOpt.addList();
1067 bKp.addString(
"Kp");
1068 Bottle &bKpVal=bKp.addList();
1069 bKpVal.addFloat64(kp);
1071 Bottle &bKi=stereoOpt.addList();
1072 bKi.addString(
"Ki");
1073 Bottle &bKiVal=bKi.addList();
1074 bKiVal.addFloat64(ki);
1076 Bottle &bKd=stereoOpt.addList();
1077 bKd.addString(
"Kd");
1078 Bottle &bKdVal=bKd.addList();
1079 bKdVal.addFloat64(kd);
1081 Bottle &bTs=stereoOpt.addList();
1082 bTs.addString(
"Ts");
1083 bTs.addFloat64(0.05);
1085 Bottle &bDominantEye=stereoOpt.addList();
1086 bDominantEye.addString(
"dominantEye");
1087 dominant_eye==
LEFT?bDominantEye.addString(
"left"):bDominantEye.addString(
"right");
1089 ctrl_gaze->setStereoOptions(stereoOpt);
1092 if(neckPitchRange!=NULL && neckPitchRange->size()==1)
1094 double neckPitchBlock=neckPitchRange->get(0).asFloat64();
1095 ctrl_gaze->blockNeckPitch(neckPitchBlock);
1097 else if(neckPitchRange!=NULL && neckPitchRange->size()>1)
1099 double neckPitchMin=neckPitchRange->get(0).asFloat64();
1100 double neckPitchMax=neckPitchRange->get(1).asFloat64();
1101 ctrl_gaze->bindNeckPitch(neckPitchMin,neckPitchMax);
1103 if(neckRollRange!=NULL && neckRollRange->size()==1)
1105 double neckRollBlock=neckRollRange->get(0).asFloat64();
1106 ctrl_gaze->blockNeckRoll(neckRollBlock);
1108 else if(neckRollRange!=NULL && neckRollRange->size()>1)
1110 double neckRollMin=neckRollRange->get(0).asFloat64();
1111 double neckRollMax=neckRollRange->get(1).asFloat64();
1112 ctrl_gaze->bindNeckRoll(neckRollMin,neckRollMax);
1115 if (bMotor.check(
"block_eyes"))
1117 ctrl_gaze->blockEyes(bMotor.find(
"block_eyes").asFloat64());
1118 ctrl_gaze->waitMotionDone();
1122 ctrl_gaze->storeContext(&gaze_context);
1123 ctrl_gaze->restoreContext(initial_gaze_context);
1124 ctrl_gaze->deleteContext(initial_gaze_context);
1125 gazeUnderControl=
false;
1130 string exploration_name=bMotor.find(
"exploration_poses").asString();
1131 if(!loadExplorationPoses(exploration_name))
1133 yError(
"Error while loading exploration poses!");
1139 Property netOptions;
1140 string net_name=bMotor.find(
"net").asString();
1141 netOptions.fromConfigFile(rf.findFile(net_name));
1144 yInfo(
"Neural network configured successfully");
1145 neuralNetworkAvailable=
true;
1149 yError(
"Error while loading neural network!");
1150 neuralNetworkAvailable=
false;
1154 if(!getGeneralOptions(bMotor))
1156 yError(
"Error extracting general options!");
1162 bArm[
LEFT]=rf.findGroup(
"left_arm");
1163 bArm[
RIGHT]=rf.findGroup(
"right_arm");
1167 for (
int i=1; i<bMotor.size(); i++)
1169 Bottle *pB=bMotor.get(i).asList();
1172 if(pB->get(0).asString()==
"hand_sequences_file")
1174 string hand_seq_name=bMotor.find(
"hand_sequences_file").asString();
1175 option.put(
"hand_sequences_file",rf.findFile(hand_seq_name));
1178 option.put(pB->get(0).asString(),pB->get(1));
1182 yError(
"Error: invalid option!");
1189 vector<double> torso_stiffness(0),torso_damping(0);
1190 Bottle *bImpedanceTorsoStiff=bMotor.find(
"impedence_torso_stiffness").asList();
1191 Bottle *bImpedanceTorsoDamp=bMotor.find(
"impedence_torso_damping").asList();
1193 for(
int i=0; i<bImpedanceTorsoStiff->size(); i++)
1195 torso_stiffness.push_back(bImpedanceTorsoStiff->get(i).asFloat64());
1196 torso_damping.push_back(bImpedanceTorsoDamp->get(i).asFloat64());
1199 for(
int i=0; i<bImpedanceTorsoStiff->size(); i++)
1200 ctrl_impedance_torso->setImpedance(i,torso_stiffness[i],torso_damping[i]);
1203 vector<double> arm_stiffness(0),arm_damping(0);
1204 Bottle *bImpedanceArmStiff=bMotor.find(
"impedence_arm_stiffness").asList();
1205 Bottle *bImpedanceArmDamp=bMotor.find(
"impedence_arm_damping").asList();
1207 for(
int i=0; i<bImpedanceArmStiff->size(); i++)
1209 arm_stiffness.push_back(bImpedanceArmStiff->get(i).asFloat64());
1210 arm_damping.push_back(bImpedanceArmDamp->get(i).asFloat64());
1213 option.put(
"local",name);
1215 default_exec_time=option.check(
"default_exec_time",Value(
"3.0")).asFloat64();
1216 reachingTimeout=std::max(2.0*default_exec_time,4.0);
1218 string arm_name[]={
"left_arm",
"right_arm"};
1219 for (
int arm=0; arm<2; arm++)
1221 if (partUsed==
"both_arms" || (partUsed==
"left_arm" && arm==
LEFT)
1222 || (partUsed==
"right_arm" && arm==
RIGHT))
1225 if (bArm[arm].isNull())
1227 yError(
"Missing %s parameter list!",arm_name[arm].c_str());
1231 else if(!getArmOptions(bArm[arm],arm))
1233 yError(
"Error extracting %s options!",arm_name[arm].c_str());
1238 Property option_tmp(option);
1239 option_tmp.put(
"part",arm_name[arm]);
1241 string tmpGraspFile=rf.findFile(bArm[arm].find(
"grasp_model_file").asString());
1242 option_tmp.put(
"grasp_model_file",tmpGraspFile);
1244 if (actionprimitives_layer==1)
1246 yInfo(
"***** Instantiating primitives layer 1 for %s",arm_name[arm].c_str());
1251 yInfo(
"***** Instantiating primitives layer 2 for %s",arm_name[arm].c_str());
1254 if (!action[arm]->isValid())
1264 p->setExtForceThres(extForceThresh[arm]);
1267 yInfo(
"***** List of available %s hand sequence keys:",arm_name[arm].c_str());
1268 for (
size_t i=0; i<q.size(); i++)
1273 yInfo(
"***** %s:",q[i].c_str());
1274 yInfo(
"%s",sequence.toString().c_str());
1277 ICartesianControl *tmpCtrl;
1281 tmpCtrl->storeContext(&context);
1283 double armTargetTol=bMotor.check(
"arm_target_tol",Value(0.01)).asFloat64();
1284 tmpCtrl->setInTargetTol(armTargetTol);
1287 tmpCtrl->restoreContext(context);
1288 tmpCtrl->deleteContext(context);
1291 if (Bottle *pB=bArm[arm].find(
"elbow_height").asList())
1295 double height=pB->get(0).asFloat64();
1296 double weight=pB->get(1).asFloat64();
1301 for(
int i=0; i<bImpedanceArmStiff->size(); i++)
1302 ctrl_impedance_arm[arm]->
setImpedance(i,arm_stiffness[i],arm_damping[i]);
1309 status_impedance_on=
false;
1310 bool impedance_from_start=bMotor.check(
"impedance",Value(
"off")).asString()==
"on";
1312 yInfo(
"Impedance set to %s",(status_impedance_on?
"on":
"off"));
1315 kinematics_file=bMotor.find(
"kinematics_file").asString();
1316 if(!loadKinematicOffsets())
1323 int starting_modeS2C=bMotor.check(
"stereoTocartesian_mode",Value(
"homography")).asVocab32();
1327 dragger.
init(rf.findGroup(
"dragger"),(
int)(1000.0*this->getPeriod()));
1329 this->avoidTable(
false);
1338 random_pos_y=bMotor.check(
"random_pos_y",Value(0.1)).asFloat64();
1343 this->
setWaveing(bMotor.check(
"waveing",Value(
"off")).asString()==
"on");
1358 if (!gazeUnderControl)
1359 gazeUnderControl=
true;
1363 ctrl_gaze->lookAtFixationPoint(
x);
1369 Vector stereo=stereo_target.
get();
1370 if(stereo.size()==4)
1376 px[
RIGHT].resize(2);
1378 px[
LEFT][0]=stereo[0];
1379 px[
LEFT][1]=stereo[1];
1380 px[
RIGHT][0]=stereo[2];
1381 px[
RIGHT][1]=stereo[3];
1383 ctrl_gaze->lookAtStereoPixels(px[
LEFT],px[
RIGHT]);
1388 if(stereo[2*dominant_eye]==0.0 && stereo[2*dominant_eye+1]==0.0)
1390 if(stereo[2*(1-dominant_eye)]==0.0 && stereo[2*(1-dominant_eye)+1]==0.0)
1393 eye_in_use=1-dominant_eye;
1396 eye_in_use=dominant_eye;
1399 px[0]=stereo[2*eye_in_use];
1400 px[1]=stereo[2*eye_in_use+1];
1401 ctrl_gaze->lookAtMonoPixel(dominant_eye,px,0.4);
1409 ctrl_gaze->lookAtFixationPoint(track_cartesian_target);
1415 if (!gazeUnderControl)
1416 gazeUnderControl=
true;
1425 Vector wrench, force(3);
1430 p->getExtWrench(wrench);
1437 dragger.
ctrl->getPose(
x,o);
1442 Bottle &tmp_action=dragger.
actions.addList();
1443 Vector tmp_x=dragger.
x0 -
x;
1445 for(
size_t i=0; i<tmp_x.size(); i++)
1446 tmp_action.addFloat64(tmp_x[i]);
1448 for(
size_t i=0; i<o.size(); i++)
1449 tmp_action.addFloat64(o[i]);
1454 dragger.
t0=Time::now();
1458 x=
x+0.1*force/
norm(force);
1467 Vector wrench, force(3);
1473 p->getExtWrench(wrench);
1484 Vector b=force/dragger.
inertia;
1485 Vector c=D*dragger.
I->
get();
1486 Vector a=force/dragger.
inertia-D*dragger.
I->
get();
1491 dragger.
ctrl->setTaskVelocities(v,zeros4d);
1503 Vector stereoHand=stereo_target.
get();
1504 if(stereoHand.size()==4)
1519 for(
int arm=0; arm<2; arm++)
1521 if(action[arm]!=NULL)
1526 Vector head_x,head_o;
1527 ctrl_gaze->getHeadPose(head_x,head_o);
1529 if(fabs(
x[1]-head_x[1])<0.2)
1530 x[1]=head_x[1]+sign(
x[1]-head_x[1])*0.2;
1532 ICartesianControl *tmp_ctrl;
1534 x[2]=avoid_table_height[arm];
1536 tmp_ctrl->goToPosition(
x);
1555 if(action[
LEFT]!=NULL)
1558 if(action[
RIGHT]!=NULL)
1566 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
1567 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1573 x[2]+=(std::isnan(
h)?go_up_distance:
h);
1588 if (checkOptions(options,
"left") ||
1589 checkOptions(options,
"right"))
1590 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1592 Bottle *bTarget=options.find(
"target").asList();
1598 arm=checkArm(arm,xd);
1600 if (!checkOptions(options,
"no_head") &&
1601 !checkOptions(options,
"no_gaze"))
1604 options.addString(
"fixate");
1608 bool side=checkOptions(options,
"side");
1609 Vector tmpOrient,tmpDisp;
1613 tmpOrient=reachSideOrient[arm];
1614 tmpDisp=reachSideDisp[arm];
1618 tmpOrient=(checkOptions(options,
"take")?
1619 reachAboveOrient[arm]:
1620 reachAboveCata[arm]);
1621 tmpDisp=reachAboveDisp;
1623 if (checkOptions(options,
"touch"))
1624 xd[2]=std::min(xd[2],table_height-table_height_tolerance);
1627 restoreContext(arm);
1631 p->enableContactDetection();
1634 wp.
x=xd+tmpDisp; wp.
o=tmpOrient; wp.
oEnabled=
true;
1635 deque<ActionPrimitivesWayPoint> wpList;
1636 wpList.push_back(wp);
1638 wpList.push_back(wp);
1641 if (checkOptions(options,
"pretake_hand"))
1642 action[arm]->
pushAction(wpList,
"pretake_hand");
1651 p->disableContactDetection();
1670 if (!checkOptions(options,
"no_head") &&
1671 !checkOptions(options,
"no_gaze"))
1681 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
1682 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1684 Bottle *bTarget=options.find(
"target").asList();
1692 arm=checkArm(arm,xd,
false);
1693 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1696 options.addString(
"fixate");
1700 Vector approach_data(4,0.0);
1701 if (options.check(
"approach"))
1703 if (Bottle *bApproach=options.find(
"approach").asList())
1705 size_t sz=std::min(approach_data.size(),(
size_t)bApproach->size());
1706 for (
size_t i=0; i<sz; i++)
1707 approach_data[i]=bApproach->get(i).asFloat64();
1711 Vector
x=xd.subVector(0,2);
1712 Vector o=xd.subVector(3,6);
1714 Matrix R=axis2dcm(o);
1715 Vector
y=R.getCol(1);
1718 Vector dx=approach_data[0]*R.getCol(0).subVector(0,2);
1719 Vector dy=approach_data[1]*R.getCol(1).subVector(0,2);
1720 Vector dz=approach_data[2]*R.getCol(2).subVector(0,2);
1722 Vector approach_x=
x+dx+dy+dz;
1723 Vector approach_o=dcm2axis(axis2dcm(
y)*R);
1725 restoreContext(arm);
1729 p->enableContactDetection();
1731 action[arm]->
pushAction(approach_x,approach_o,
"pregrasp_hand");
1738 p->disableContactDetection();
1740 return grasp(options);
1747 if (checkOptions(options,
"left") || checkOptions(options,
"right"))
1748 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1753 arm=checkArm(arm,xd);
1755 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1758 options.addString(
"fixate");
1763 xd+=pushAboveRelief;
1764 double push_direction=checkOptions(options,
"away")?-1.0:1.0;
1765 Vector tmpDisp=push_direction*reachSideDisp[arm];
1766 Vector tmpOrient=reachSideOrient[arm];
1768 restoreContext(arm);
1771 action[arm]->
pushAction(xd+tmpDisp,tmpOrient);
1774 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1777 ctrl_gaze->restoreContext(gaze_context);
1784 p->enableContactDetection();
1785 action[arm]->
pushAction(xd-3*push_direction*reachSideDisp[arm],reachSideOrient[arm]);
1788 p->disableContactDetection();
1790 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1800 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
1801 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1803 Bottle *bTarget=options.find(
"target").asList();
1809 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1815 arm=checkArm(arm,xd);
1816 xd[0]=std::min(xd[0]+0.07,-0.15);
1817 xd[1]+=(arm==
LEFT)?-0.05:0.05;
1820 Matrix R=
zeros(3,3);
1822 R(1,1)=(arm==
LEFT)?-1.0:1.0;
1823 R(2,2)=(arm==
LEFT)?1.0:-1.0;
1825 restoreContext(arm);
1827 Vector od=dcm2axis(R);
1828 action[arm]->
pushAction(xd,od,
"pointing_hand");
1832 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1835 ctrl_gaze->setTrackingMode(
false);
1845 Bottle *bTarget=options.find(
"target").asList();
1850 if (checkOptions(options,
"left"))
1852 else if (checkOptions(options,
"right"))
1855 arm=checkArm(arm,xd);
1857 restoreContext(arm);
1858 ICartesianControl* iarm;
1861 Property requirements;
1863 requirements.put(
"point",
point.get(0));
1865 Bottle pointing_sequence;
1866 if (action[arm]->getHandSequence(
"pointing_hand",pointing_sequence))
1868 int numWayPoints=pointing_sequence.find(
"numWayPoints").asInt32();
1869 ostringstream wp; wp<<
"wp_"<<numWayPoints-1;
1870 Bottle *poss=pointing_sequence.find(wp.str()).asList()->find(
"poss").asList();
1871 Vector joints(poss->size());
1872 for (
size_t i=0; i<joints.length(); i++)
1873 joints[i]=poss->get(i).asFloat64();
1875 Bottle finger_joints; finger_joints.addList().read(joints);
1876 requirements.put(
"finger-joints",finger_joints.get(0));
1882 if (!checkOptions(options,
"no_head") &&
1883 !checkOptions(options,
"no_gaze"))
1886 options.addString(
"fixate");
1893 if (!checkOptions(options,
"no_head") &&
1894 !checkOptions(options,
"no_gaze"))
1897 ctrl_gaze->setTrackingMode(
false);
1908 ctrl_gaze->restoreContext(gaze_context);
1910 if (checkOptions(options,
"hand"))
1913 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
1914 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1922 Bottle *bTarget=options.find(
"target").asList();
1926 if (options.check(
"block_eyes"))
1928 ctrl_gaze->blockEyes(options.find(
"block_eyes").asFloat64());
1929 ctrl_gaze->waitMotionDone();
1932 if (checkOptions(options,
"fixate"))
1935 ctrl_gaze->lookAtFixationPointSync(xd);
1936 if (checkOptions(options,
"wait"))
1937 ctrl_gaze->waitMotionDone();
1947 if (checkOptions(options,
"left") || checkOptions(options,
"right"))
1948 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1951 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1957 restoreContext(arm);
1958 action[arm]->
pushAction(takeToolPos[arm],takeToolOrient[arm],
"open_hand");
1963 double force_thresh;
1965 p->getExtForceThres(force_thresh);
1967 bool contact_detected=
false;
1969 double t=Time::now();
1971 while (!contact_detected && (Time::now()-t<5.0))
1974 p->getExtWrench(wrench);
1976 if (
norm(wrench)>force_thresh)
1977 contact_detected=
true;
1982 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
1992 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
1993 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
1997 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2003 restoreContext(arm);
2004 action[arm]->
pushAction(expectPos[arm],expectOrient[arm],
"open_hand");
2009 double force_thresh;
2011 p->getExtForceThres(force_thresh);
2013 bool contact_detected=
false;
2015 double t=Time::now();
2016 while(!contact_detected && Time::now()-t<5.0)
2019 p->getExtWrench(wrench);
2021 if(
norm(wrench)>force_thresh)
2022 contact_detected=
true;
2027 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2037 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
2038 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2042 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2048 restoreContext(arm);
2049 action[arm]->
pushAction(expectPos[arm],expectOrient[arm]);
2057 p->enableContactDetection();
2059 bool contact_detected=
false;
2060 double t=Time::now();
2061 while (!contact_detected && (Time::now()-t<5.0))
2064 p->checkContact(contact_detected);
2069 p->disableContactDetection();
2071 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2081 ctrl_gaze->setSaccadesMode(
false);
2090 if (checkOptions(options,
"left") || checkOptions(options,
"right"))
2091 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2098 if (options.size()<2)
2100 yError(
"Too few arguments for HAND command!");
2103 action_type=options.get(1).asString();
2108 if (action[arm]->pushAction(action_type))
2118 yError(
"Unknown hand sequence \"%s\"",action_type.c_str());
2127 if (
hand(options,
"close_hand",&holding))
2136 hand(options,
"release_hand");
2142 const double weight)
2145 if (action[arm]!=NULL)
2147 ICartesianControl *ctrl;
2150 ctrl->stopControl();
2153 ctrl->storeContext(&context);
2155 restoreContext(arm);
2157 Bottle tweakOptions;
2158 Bottle &optTask2=tweakOptions.addList();
2159 optTask2.addString(
"task_2");
2160 Bottle &plTask2=optTask2.addList();
2161 plTask2.addInt32(6);
2162 Bottle &posPart=plTask2.addList();
2163 posPart.addFloat64(0.0);
2164 posPart.addFloat64(0.0);
2165 posPart.addFloat64(height);
2166 Bottle &weightsPart=plTask2.addList();
2167 weightsPart.addFloat64(0.0);
2168 weightsPart.addFloat64(0.0);
2169 weightsPart.addFloat64(weight);
2170 ret=ctrl->tweakSet(tweakOptions);
2175 ctrl->restoreContext(context);
2176 ctrl->deleteContext(context);
2187 default_exec_time=execTime;
2188 reachingTimeout=std::max(2.0*default_exec_time,4.0);
2192 if (action[arm]!=NULL)
2194 ICartesianControl *ctrl;
2197 ctrl->stopControl();
2200 ctrl->storeContext(&context);
2202 restoreContext(arm);
2209 ctrl->restoreContext(context);
2210 ctrl->deleteContext(context);
2222 const Vector &xin,
const Vector &oin)
2224 ICartesianControl *ctrl;
2228 ctrl->stopControl();
2229 ctrl->storeContext(&tmp_ctxt);
2232 ctrl->getDOF(dof); dof=1.0;
2233 ctrl->setDOF(dof,dof);
2235 ctrl->setLimits(0,0.0,0.0);
2236 ctrl->setLimits(1,0.0,0.0);
2237 ctrl->setLimits(2,0.0,0.0);
2239 ctrl->setTrajTime(default_exec_time);
2240 ctrl->setInTargetTol(0.04);
2242 ctrl->goToPoseSync(xin,oin);
2243 ctrl->waitMotionDone(0.1,reachingTimeout);
2245 ctrl->stopControl();
2246 ctrl->restoreContext(tmp_ctxt);
2252 bool head_home=(checkOptions(options,
"head") || checkOptions(options,
"gaze"));
2253 bool arms_home=(checkOptions(options,
"arms") || checkOptions(options,
"arm"));
2254 bool hand_home=(checkOptions(options,
"fingers") || checkOptions(options,
"hands") ||
2255 checkOptions(options,
"hand"));
2258 if (!head_home && !arms_home && !hand_home)
2259 head_home=arms_home=hand_home=
true;
2262 head_home = head_home && !checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze");
2264 bool left_arm=checkOptions(options,
"left") || checkOptions(options,
"both");
2265 bool right_arm=checkOptions(options,
"right") || checkOptions(options,
"both");
2268 if (!left_arm && !right_arm)
2269 left_arm=right_arm=
true;
2274 ctrl_gaze->restoreContext(gaze_context);
2275 ctrl_gaze->setTrackingMode(
true);
2277 if (homeFixCartType)
2278 ctrl_gaze->lookAtFixationPointSync(homeFix);
2280 ctrl_gaze->lookAtAbsAnglesSync(homeFix);
2287 exec_arm[0]=left_arm;
2288 exec_arm[1]=right_arm;
2293 if (exec_arm[0] && exec_arm[1])
2295 if (armInUse==
RIGHT)
2302 for (
size_t i=0; i<2; i++)
2304 if (exec_arm[i] && (action[which_arm[i]]!=NULL))
2307 action[which_arm[i]]->
pushAction(
"open_hand");
2309 goWithTorsoUpright(action[which_arm[i]],homePos[which_arm[i]],homeOrient[which_arm[i]]);
2316 if (waveing && right_arm && (action[
RIGHT]!=NULL))
2319 if (waveing && left_arm && (action[
LEFT]!=NULL))
2333 ctrl_gaze->waitMotionDone(0.1,3.0);
2334 ctrl_gaze->stopControl();
2335 ctrl_gaze->setTrackingMode(
false);
2345 if (checkOptions(options,
"left") || checkOptions(options,
"right"))
2346 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2353 Bottle *bTarget=options.find(
"target").asList();
2358 deployZone=deployPos[arm];
2359 if (checkOptions(options,
"away"))
2361 deployZone[0]=-0.15;
2362 deployZone[1]=(arm==
LEFT)?deployZone[1]=-0.35:deployZone[1]=0.35;
2365 deployZone=deployZone+randomDeployOffset();
2366 deployZone[2]=table_height;
2370 arm=checkArm(arm,deployZone);
2371 if (checkOptions(options,
"gently") && !checkOptions(options,
"over"))
2372 deployZone[2]=table_height;
2375 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2378 ctrl_gaze->restoreContext(gaze_context);
2380 ctrl_gaze->lookAtFixationPoint(deployZone);
2383 Vector tmpOrient=(grasp_state==
GRASP_STATE_SIDE?reachSideOrient[arm]:deployOrient[arm]);
2385 Vector deployOffs(deployZone.length(),0.0);
2386 deployOffs[2]=reachAboveDisp[2];
2388 restoreContext(arm);
2391 action[arm]->
pushAction(deployZone+deployOffs,tmpOrient);
2396 p->enableContactDetection();
2400 wp.
x=deployZone+deployOffs; wp.
o=tmpOrient; wp.
oEnabled=
true;
2401 deque<ActionPrimitivesWayPoint> wpList;
2402 wpList.push_back(wp);
2404 wpList.push_back(wp);
2411 p->disableContactDetection();
2413 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2414 ctrl_gaze->lookAtFixationPoint(
x);
2424 if (checkOptions(options,
"left") ||
2425 checkOptions(options,
"right"))
2426 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2429 goWithTorsoUpright(action[arm],drawNearPos[arm],drawNearOrient[arm]);
2431 Bottle look_options;
2432 Bottle &target=look_options.addList();
2433 target.addString(
"target");
2434 Bottle &payLoad=target.addList().addList();
2435 payLoad.addString(
"cartesian");
2436 payLoad.addList().read(drawNearPos[arm]);
2437 look_options.addString(
"wait");
2447 if (checkOptions(options,
"left") ||
2448 checkOptions(options,
"right"))
2449 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2458 action[arm]->
pushAction(
x,reachAboveOrient[arm],
"close_hand");
2472 Vector x_hand,o_hand,px[2],x_head,o_head;
2473 action[arm]->
getPose(x_hand,o_hand);
2474 ctrl_gaze->get2DPixel(
LEFT,x_hand,px[
LEFT]);
2475 ctrl_gaze->get2DPixel(
RIGHT,x_hand,px[
RIGHT]);
2477 ctrl_gaze->getHeadPose(x_head,o_head);
2479 hand_image_pos.clear();
2480 hand_image_pos.addFloat64(px[
LEFT][0]);
2481 hand_image_pos.addFloat64(px[
LEFT][1]);
2482 hand_image_pos.addFloat64(px[
RIGHT][0]);
2483 hand_image_pos.addFloat64(px[
RIGHT][1]);
2484 hand_image_pos.addFloat64(
norm(x_head-x_hand));
2493 if (checkOptions(options,
"left") ||
2494 checkOptions(options,
"right"))
2495 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2502 return !in_position;
2509 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
2510 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2514 Vector deployZone=deployPos[arm];
2515 deployZone=deployZone+randomDeployOffset();
2517 Vector deployPrepare,deployEnd;
2518 deployPrepare=deployEnd=deployZone;
2520 deployPrepare[2]=0.0;
2525 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2528 ctrl_gaze->restoreContext(gaze_context);
2529 ctrl_gaze->lookAtFixationPoint(deployEnd);
2535 restoreContext(arm);
2539 p->enableContactDetection();
2542 wp.
x=deployPrepare; wp.
o=reachAboveCata[arm];
2544 deque<ActionPrimitivesWayPoint> wpList;
2545 wpList.push_back(wp);
2547 wpList.push_back(wp);
2554 p->disableContactDetection();
2559 p->checkContact(found);
2566 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2567 ctrl_gaze->lookAtFixationPoint(
x);
2570 table[3]=-table_height;
2572 bKinOffsets.find(
"table_height")=Value(table_height);
2575 saveKinematicOffsets();
2580 yWarning(
"########## Table height found: %f",table_height);
2583 table_height+=table_height_tolerance;
2586 yWarning(
"########## Table height not found!");
2588 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2599 int currentArm=armInUse;
2601 int handToCalibrate=-1;
2602 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
2603 handToCalibrate=checkOptions(options,
"left")?
LEFT:
RIGHT;
2605 bool no_head=(checkOptions(options,
"no_head"));
2607 bool calibrated=
true;
2608 for(
int arm=0; arm<2; arm++)
2610 if(action[arm]!=NULL && (handToCalibrate==-1 || handToCalibrate==arm))
2617 Bottle b(arm==
LEFT?
"left":
"right");
2621 Bottle &fng=fingers.addList();
2622 fng.addString(
"index");
2623 fng.addString(
"middle");
2624 fng.addString(
"ring");
2625 fng.addString(
"little");
2628 prop.put(
"finger",fingers.get(0));
2632 prop.put(
"finger",
"thumb");
2636 std::filesystem::path fileName(rf.getHomeContextPath()+
"/"+graspFile[arm]);
2637 std::filesystem::create_directories(fileName.parent_path());
2638 fout.open(fileName);
2642 calibrated=calibrated && graspModel[arm]->
isCalibrated();
2645 action[arm]->
pushAction(homePos[arm],homeOrient[arm],
"open_hand");
2653 options.addString(
"head");
2663bool MotorThread::avoidTable(
bool avoid)
2665 for(
int arm=0; arm<2; arm++)
2667 if(action[arm]!=NULL)
2673 avoid_table_height[arm]=
x[2];
2685 this->avoidTable(
true);
2688 ctrl_gaze->getInfo(info);
2689 iKinLimbVersion head_version(info.check(
"head_version",Value(
"1.0")).asString());
2692 type<<(dominant_eye==
LEFT?
"left":
"right");
2699 for (
unsigned int i=2; i<iKinTorso.
getN(); i++)
2703 Vector torso_init_joints(3);
2704 enc_torso->getEncoders(torso_init_joints.data());
2708 Vector tmp_joints(2,0.0);
2711 iKinTorso.
setAng(tmp_joints);
2714 Matrix
H=iKinTorso.
getH(3,
true);
2715 Vector cart_init_pos(3);
2716 cart_init_pos[0]=
H[0][3];
2717 cart_init_pos[1]=
H[1][3];
2718 cart_init_pos[2]=
H[2][3];
2722 Vector fixed_target(3);
2723 fixed_target[0]=-0.5;
2724 fixed_target[1]=0.0;
2725 fixed_target[2]=cart_init_pos[2];
2727 double walking_time=20.0;
2728 double step_time=2.0;
2729 double kp_pos_torso=0.6;
2731 vector<int> modes(3,VOCAB_CM_VELOCITY);
2732 ctrl_mode_torso->setControlModes(modes.data());
2734 double init_walking_time=Time::now();
2737 while(this->isRunning() && !interrupted && Time::now()-init_walking_time<walking_time)
2740 Vector random_pos=cart_init_pos;
2741 if (Rand::scalar(0.0,3.0)>2.0)
2742 random_pos[0]+=Rand::scalar(-0.1,-0.05);
2745 double tmp_rnd=Rand::scalar(-random_pos_y,random_pos_y);
2746 if ((tmp_rnd>-0.1) && (tmp_rnd<0.1))
2747 tmp_rnd=0.1*yarp::math::sign(tmp_rnd);
2749 random_pos[1]+=tmp_rnd;
2752 random_pos=(
norm(cart_init_pos)/
norm(random_pos))*random_pos;
2755 double init_step_time=Time::now();
2756 while(this->isRunning() && !interrupted && Time::now()-init_step_time<step_time && Time::now()-init_walking_time<walking_time)
2759 Vector torso_joints(3);
2760 enc_torso->getEncoders(torso_joints.data());
2762 Vector tmp_joints(2,0.0);
2765 iKinTorso.
setAng(tmp_joints);
2768 Matrix
H=iKinTorso.
getH(3,
true);
2770 curr_pos[0]=
H[0][3];
2771 curr_pos[1]=
H[1][3];
2772 curr_pos[2]=
H[2][3];
2774 Vector x_dot=kp_pos_torso*(random_pos-curr_pos);
2775 Matrix J=iKinTorso.
GeoJacobian(3).submatrix(0,2,0,1);
2776 Matrix J_pinv=pinv(J,1
e-06);
2778 double q_dot_mag=
norm(q_dot);
2779 double q_dot_saturation=15.0;
2786 else if (q_dot_mag>q_dot_saturation)
2787 q_dot=(q_dot_saturation/q_dot_mag)*q_dot;
2790 vector<int>
jnts(2);
2793 vel_torso->velocityMove((
int)
jnts.size(),
jnts.data(),q_dot.data());
2799 modes[0]=modes[1]=modes[2]=VOCAB_CM_POSITION;
2800 ctrl_mode_torso->setControlModes(modes.data());
2801 pos_torso->positionMove(torso_init_joints.data());
2803 while (isRunning() && !
done)
2806 pos_torso->checkMotionDone(&
done);
2809 this->avoidTable(
false);
2818 yError(
"Error! The requested arm is busy!");
2823 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
2824 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2828 if(action[arm]==NULL)
2830 yError(
"Error! requested arm is not working!");
2835 int other_arm=1-arm;
2836 if(!checkOptions(options,
"keep_other_hand_still") && action[other_arm]!=NULL)
2838 action[other_arm]->
pushAction(homePos[other_arm],homeOrient[other_arm]);
2845 Bottle bInterrupt(
"skip");
2854 if(!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2861 double max_step_time=2.0;
2864 enc_arm[arm]->getAxes(&nJnts);
2866 vector<int> modes(nJnts,VOCAB_CM_POSITION);
2867 ctrl_mode_arm[arm]->setControlModes(modes.data());
2870 Vector destination(nJnts);
2871 for(
unsigned int pose_idx=0; pose_idx<handPoses.size(); pose_idx++)
2873 Vector current_position(nJnts);
2874 enc_arm[arm]->getEncoders(current_position.data());
2877 for(
unsigned int i=0; i<handPoses[pose_idx].size(); i++)
2878 destination[i]=handPoses[pose_idx][i];
2881 for(
int i=handPoses[pose_idx].size(); i<nJnts; i++)
2882 destination[i]=current_position[i];
2884 pos_arm[arm]->positionMove(destination.data());
2886 double init_step_time=Time::now();
2887 while(!this->interrupted && Time::now()-init_step_time<max_step_time)
2889 enc_arm[arm]->getEncoders(current_position.data());
2892 for(
size_t i=0; i<handPoses[pose_idx].size(); i++)
2893 if(fabs(destination[i]-current_position[i])>3.0)
2903 if (!checkOptions(options,
"no_head") && !checkOptions(options,
"no_gaze"))
2907 if(action[arm]!=NULL)
2921 yError(
"Error: The requested arm is busy!");
2925 string action_name=options.find(
"action_name").asString();
2929 yError(
"action name not specified!");
2934 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
2935 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
2939 string arm_name=(arm==
LEFT?
"left":
"right");
2941 string fileName=rf.findFile(actions_path+
"/"+arm_name+
"/"+action_name+
".action");
2942 if(!fileName.empty())
2944 yWarning(
"Action '%s' already learned... stopping",action_name.c_str());
2955 if(dragger.
ctrl==NULL)
2957 yError(
"Could not find the cartesian arm interface!");
2964 dragger.
ctrl->getPose(
x,o);
2969 yError(
"Could not set torque control mode!");
2973 dragger.
t0=Time::now();
2985 string arm_name=(dragger.
arm==
LEFT?
"left":
"right");
2988 bool skip=checkOptions(options,
"skip");
2992 if (!actions_path.empty())
2994 std::filesystem::path fileName=rf.getHomeContextPath();
2995 fileName+=
"/"+actions_path+
"/"+arm_name+
"/"+dragger.
actionName+
".action";
2996 std::filesystem::create_directories(fileName.parent_path());
2997 ofstream action_fout(fileName);
2998 if(!action_fout.is_open())
3000 yError(
"Unable to open file '%s' for action %s!",(actions_path+
"/"+arm_name+
"/"+dragger.
actionName+
".action").c_str(),dragger.
actionName.c_str());
3004 action_fout << dragger.
actions.toString();
3025 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
3026 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
3030 string arm_name=arm==
LEFT?
"left":
"right";
3031 string action_name=options.find(
"action_name").asString();
3034 string fileName=rf.findFile(actions_path+
"/"+arm_name+
"/"+action_name+
".action");
3035 if (!fileName.empty())
3037 ifstream action_fin(fileName.c_str());
3038 if(!action_fin.is_open())
3041 stringstream strstr;
3042 strstr << action_fin.rdbuf();
3043 actions.fromString(strstr.str());
3045 else if (!opcPort.
getAction(action_name, &actions))
3048 restoreContext(arm);
3050 ICartesianControl *ctrl;
3054 ctrl->getDOF(newPos);
3055 newPos[0]=newPos[1]=0.0; newPos[2]=1.0;
3056 ctrl->setDOF(newPos,newPos);
3057 ctrl->setInTargetTol(0.01);
3058 ctrl->setTrajTime(0.75);
3060 Vector init_x,init_o;
3061 ctrl->getPose(init_x,init_o);
3063 for(
int i=0; i<actions.size(); i++)
3065 Bottle *b=actions.get(i).asList();
3067 for(
int j=0; j<3; j++)
3068 x[j]=b->get(j).asFloat64();
3070 for(
int j=0; j<4; j++)
3071 o[j]=b->get(j+3).asFloat64();
3073 ctrl->goToPoseSync(init_x-
x,o);
3077 ctrl->waitMotionDone(0.1,reachingTimeout);
3078 restoreContext(arm);
3091 if(checkOptions(options,
"left") || checkOptions(options,
"right"))
3092 arm=checkOptions(options,
"left")?
LEFT:
RIGHT;
3094 dragger.
arm=checkArm(arm);
3100 if(dragger.
ctrl==NULL)
3102 yError(
"Could not find the arm controller!");
3109 yWarning(
"Impedance control not available. Using admittance control!");
3112 bool specifiedTarget=
false;
3113 if (Bottle *b0=options.find(
"target").asList())
3115 if (Bottle *b1=b0->find(
"cartesian").asList())
3117 size_t n=std::min(
x.length(),(
size_t)b1->size());
3118 for (
size_t i=0; i<
n; i++)
3119 x[i]=b1->get(i).asFloat64();
3120 specifiedTarget=
true;
3124 if (!specifiedTarget)
3127 dragger.
ctrl->getPose(
x,o);
3131 dragger.
t0=Time::now();
3132 yInfo(
"Learning kinematic offset against %s target (%s)",
3133 specifiedTarget?
"specified":
"retrieved",
3134 dragger.
x0.toString(3,3).c_str());
3138 Bottle look_options;
3139 look_options.addString(
"hand");
3140 look_options.addString(dragger.
arm==
LEFT?
"left":
"right");
3152 bool skip=checkOptions(options,
"skip");
3158 dragger.
ctrl->getPose(
x,o);
3160 if (options.size()>=4)
3162 currentKinematicOffset[dragger.
arm]=
x-(dragger.
x0-currentKinematicOffset[dragger.
arm]);
3165 if(options.size()<4 || !opcPort.
setKinematicOffsets(options.get(3).asString(),currentKinematicOffset))
3167 defaultKinematicOffset[dragger.
arm]=currentKinematicOffset[dragger.
arm];
3171 for(
int i=0; i<3; i++)
3172 bOffset.addFloat64(defaultKinematicOffset[dragger.
arm][i]);
3174 string arm_name=(dragger.
arm==
LEFT?
"left":
"right");
3175 *bKinOffsets.find(arm_name).asList()->find(Vocab32::decode(modeS2C)).asList()=bOffset;
3177 saveKinematicOffsets();
3195 Bottle &gaze=status.addList();
3196 gaze.addString(
"gaze");
3199 gaze.addString(
"busy");
3201 gaze.addString(
"idle");
3203 Bottle &control_mode=status.addList();
3204 control_mode.addString(
"control mode");
3205 control_mode.addString(status_impedance_on?
"impedance":
"velocity");
3207 Bottle &left_arm=status.addList();
3208 left_arm.addString(
"left_arm");
3210 if(action[
LEFT]!=NULL)
3216 left_arm.addString(
"busy");
3218 left_arm.addString(
"idle");
3221 left_arm.addString(
"unavailable");
3224 Bottle &right_arm=status.addList();
3225 right_arm.addString(
"right_arm");
3227 if(action[
RIGHT]!=NULL)
3233 right_arm.addString(
"busy");
3235 right_arm.addString(
"idle");
3238 right_arm.addString(
"unavailable");
3242 Bottle &statusS2C=status.addList();
3243 statusS2C.addString(
"[Stereo -> Cartesian] mode: ");
3249 statusS2C.addString(
"homography");
3255 statusS2C.addString(
"disparity");
3261 statusS2C.addString(
"network");
3274 table.resize(4,0.0);
3276 table[3]=-table_height;
3279 table_height+=table_height_tolerance;
3288 disparityPort.interrupt();
3291 Bottle bInterrupt(
"skip");
3295 if (ctrl_gaze!=NULL)
3298 ctrl_gaze->stopControl();
3301 if(action[
LEFT]!=NULL)
3308 if(action[
RIGHT]!=NULL)
3319 if(action[
LEFT]!=NULL)
3325 if(action[
RIGHT]!=NULL)
3331 disparityPort.resume();
#define HEAD_MODE_TRACK_TEMP
#define ARM_MODE_LEARN_ACTION
#define HEAD_MODE_TRACK_HAND
#define HEAD_MODE_TRACK_CART
#define ARM_MODE_LEARN_KINOFF
#define ARM_MODE_FINE_REACHING
#define HEAD_MODE_TRACK_FIX
bool push(Bottle &options)
bool targetToCartesian(Bottle *target, Vector &xd)
bool calibTable(Bottle &options)
bool setArmInUse(int arm)
bool powerGrasp(Bottle &options)
void keepFixation(Bottle &options)
bool startLearningModeAction(Bottle &options)
virtual bool threadInit()
bool reach(Bottle &options)
bool grasp(const Bottle &options)
bool drawNear(Bottle &options)
bool isHolding(const Bottle &options)
bool stereoToCartesian(const Vector &stereo, Vector &xd)
bool clearIt(Bottle &options)
void getStatus(Bottle &status)
bool point(Bottle &options)
bool startLearningModeKinOffset(Bottle &options)
bool hand(const Bottle &options, const string &type="", bool *holding=NULL)
bool give(Bottle &options)
void lookAtHand(Bottle &options)
bool point_far(Bottle &options)
bool imitateAction(Bottle &options)
bool exploreHand(Bottle &options)
virtual void threadRelease()
bool look(Bottle &options)
bool deploy(Bottle &options)
bool suspendLearningModeKinOffset(Bottle &options)
bool exploreTorso(Bottle &options)
bool changeElbowHeight(const int arm, const double height, const double weight)
bool suspendLearningModeAction(Bottle &options)
bool setTorque(bool turn_on, int arm=ARM_IN_USE)
bool setImpedance(bool turn_on)
bool changeExecTime(const int arm, const double execTime)
bool release(const Bottle &options)
bool takeTool(Bottle &options)
bool calibFingers(Bottle &options)
bool setWaveing(bool _waveing)
void setGraspState(bool side)
bool shiftAndGrasp(Bottle &options)
bool getHandImagePosition(Bottle &hand_image_pos)
bool goHome(Bottle &options)
int setStereoToCartesianMode(const int mode, Bottle &reply)
bool goUp(Bottle &options, const double h=std::numeric_limits< double >::quiet_NaN())
bool expect(Bottle &options)
bool getKinematicOffsets(const string &obj_name, Vector *kinematic_offset)
bool getTableHeight(double &table_height)
bool setTableHeight(const double table_height)
bool getCartesianPosition(const string &obj_name, Vector &x)
bool getAction(const string &act_name, Bottle *trajectory)
bool setKinematicOffsets(const string &obj_name, const Vector *kinematic_offset)
bool setAction(const string &act_name, const Bottle *trajectory)
A derived class defining a first abstraction layer on top of actionPrimitives father class.
A class that inherits from ActionPrimitivesLayer1 and integrates the force-torque sensing in order to...
The base class defining actions.
virtual bool areFingersInPosition(bool &f)
Query if fingers are in position (cumulative response).
virtual bool lockActions()
Disable the possibility to yield any new action.
virtual bool syncCheckInterrupt(const bool disable=false)
Suddenly interrupt any blocking call that is pending on querying the action status.
virtual bool enableReachingTimeout(const double tmo)
Enable timeout while reaching.
virtual bool setTrackingMode(const bool f)
Set the task space controller in tracking or non-tracking mode.
virtual bool unlockActions()
Enable the possibility to yield new actions.
virtual bool getPose(yarp::sig::Vector &x, yarp::sig::Vector &o) const
Get the current arm pose.
virtual bool getHandSequence(const std::string &handSeqKey, yarp::os::Bottle &sequence)
Return a hand sequence.
virtual bool stopControl()
Stop any ongoing arm/hand movements.
virtual bool setDefaultExecTime(const double execTime)
Set the default arm movement execution time.
virtual bool getGraspModel(perception::Model *&model) const
Return the model used internally to detect external contacts.
virtual bool getCartesianIF(yarp::dev::ICartesianControl *&ctrl) const
Return the cartesian interface used internally to control the limb.
virtual bool pushAction(const yarp::sig::Vector &x, const yarp::sig::Vector &o, const std::string &handSeqKey, const double execTime=ACTIONPRIM_DISABLE_EXECTIME, ActionPrimitivesCallback *clb=NULL)
Insert a combination of arm and hand primitive actions in the actions queue.
std::deque< std::string > getHandSeqList()
Return the list of available hand sequence keys.
virtual bool enableArmWaving(const yarp::sig::Vector &restPos)
Enable the waving mode that keeps on moving the arm around a predefined position.
virtual bool syncCheckReinstate()
Reinstate the blocking feature for future calls with sync switch on.
virtual bool checkActionsDone(bool &f, const bool sync=false)
Check whether all the actions in queue are accomplished.
virtual bool pushWaitState(const double tmo, ActionPrimitivesCallback *clb=NULL)
Insert a wait state in the actions queue.
A class for defining a saturated integrator based on Tustin formula: .
const yarp::sig::Vector & get() const
Returns the current output vector.
const yarp::sig::Vector & integrate(const yarp::sig::Vector &x)
Executes one-step integration of input vector.
virtual bool configure(const yarp::os::Property &options)
Configure/reconfigure the network.
virtual yarp::sig::Vector predict(const yarp::sig::Vector &x) const
Predict the output given a certain input to the network.
A class for defining the iCub Eye.
yarp::sig::Matrix getH(const unsigned int i, const bool allLink=false)
Returns the rigid roto-translation matrix from the root reference frame to the ith frame in Denavit-H...
yarp::sig::Matrix GeoJacobian(const unsigned int i)
Returns the geometric Jacobian of the ith link.
bool releaseLink(const unsigned int i)
Releases the ith Link.
bool setBlockingValue(const unsigned int i, double Ang)
Changes the value of the ith blocked Link.
yarp::sig::Vector setAng(const yarp::sig::Vector &q)
Sets the free joint angles to values of q[i].
unsigned int getN() const
Returns the number of Links belonging to the Chain.
bool blockLink(const unsigned int i, double Ang)
Blocks the ith Link at the a certain value of its joint angle.
A class for defining the versions of the iCub limbs.
virtual bool toStream(std::ostream &str) const =0
Similar to the toProperty() method but it operates on output streams (e.g.
virtual bool isCalibrated() const =0
Return the internal status of the calibration.
virtual bool calibrate(const yarp::os::Property &options)=0
Some kinds of models need to be calibrated to properly operate.
double norm(const yarp::sig::Matrix &M, int col)
Returns the norm of the vector given in the form: matrix(:,col).
constexpr double CTRL_RAD2DEG
180/PI.
constexpr double CTRL_DEG2RAD
PI/180.
iCub::ctrl::Integrator * I
void init(Bottle &initializer, double thread_rate)
static bool compute(yarp::dev::ICartesianControl *iarm, const yarp::os::Property &requirements, yarp::sig::Vector &q, yarp::sig::Vector &x)
static bool point(yarp::dev::ICartesianControl *iarm, const yarp::sig::Vector &q, const yarp::sig::Vector &x)
Struct for defining way points used for movements in the operational space.
yarp::sig::Vector o
The 4x1 Vector specifying the orientation of the waypoint in axis-angle representation.
yarp::sig::Vector x
The 3x1 Vector specifyng the position of the waypoint [m].
bool oEnabled
If this flag is set to true then orientation will be taken into account.
double duration
The time duration [s] to achieve the waypoint.