AUV-Coop-Assembly
Master Thesis for Robotics Engineering. Cooperative peg-in-hole assembly with two underwater vehicles guided by vision
old_missionManager.cpp
1 #include "header/missionManager.h"
2 #include <chrono>
3 
4 
17 int main(int argc, char **argv)
18 {
19  if (argc < 3){
20  std::cout << "[MISSION_MANAGER] Please insert the two robots name"<< std::endl;
21  return -1;
22  }
23  std::string robotName = argv[1];
24  std::string otherRobotName = argv[2];
25  std::string pathLog;
26  if (LOG && (argc > 3)){ //if flag log setted to 1 and path log is given
27  pathLog = argv[3];
28  }
29 
30 
32  ros::init(argc, argv, robotName + "_MissionManager");
33  std::cout << "[" << robotName << "][MISSION_MANAGER] Start" << std::endl;
34  ros::NodeHandle nh;
35 
36 
42  double goalLinearVect[] = {-0.287, -0.090, 8};
44  Eigen::Matrix4d wTgoalVeh_eigen = Eigen::Matrix4d::Identity();
45  //rot part
46  wTgoalVeh_eigen.topLeftCorner(3,3) = Eigen::Matrix3d::Identity();
47  //trasl part
48  wTgoalVeh_eigen(0, 3) = goalLinearVect[0];
49  wTgoalVeh_eigen(1, 3) = goalLinearVect[1];
50  wTgoalVeh_eigen(2, 3) = goalLinearVect[2];
51 
53  double goalLinearVectEE[3];
54  if (robotName.compare("g500_A") == 0){
55  goalLinearVectEE[0] = 2.89;
56  goalLinearVectEE[1] = -0.090;
57  goalLinearVectEE[2] = 9.594;
58 
59  } else {
60  goalLinearVectEE[0] = -1.11;
61  goalLinearVectEE[1] = -0.090;
62  goalLinearVectEE[2] = 9.594;
63  }
64  Eigen::Matrix4d wTgoalEE_eigen = Eigen::Matrix4d::Identity();
65  //rot part
66  //wTgoalEE_eigen.topLeftCorner<3,3>() = Eigen::Matrix3d::Identity();
67  //the ee must rotate of 90 on z axis degree to catch the peg
68  wTgoalEE_eigen.topLeftCorner(3,3) << 0, -1, 0,
69  1, 0, 0,
70  0, 0, 1;
71  //trasl part
72  wTgoalEE_eigen(0, 3) = goalLinearVectEE[0];
73  wTgoalEE_eigen(1, 3) = goalLinearVectEE[1];
74  wTgoalEE_eigen(2, 3) = goalLinearVectEE[2];
75 
77  //double goalLinearVectTool[] = {-0.27, -0.102, 2.124};
78  double goalLinearVectTool[] = {-0.20, -3.102, 9.000};
79 
80  Eigen::Matrix4d wTgoalTool_eigen = Eigen::Matrix4d::Identity();
81 
82  //rot part
83  wTgoalTool_eigen.topLeftCorner<3,3>() << 0, 1, 0,
84  -1, 0, 0,
85  0, 0, 1;
86 
87  //wTgoalTool_eigen.topLeftCorner<3,3>() = Eigen::Matrix3d::Identity();
88 
89  //trasl part
90  wTgoalTool_eigen(0, 3) = goalLinearVectTool[0];
91  wTgoalTool_eigen(1, 3) = goalLinearVectTool[1];
92  wTgoalTool_eigen(2, 3) = goalLinearVectTool[2];
93 
94 
99  Infos robInfo;
101  //struct transforms to pass them to Controller class
102  robInfo.transforms.wTgoalVeh_eigen = wTgoalVeh_eigen;
103  robInfo.transforms.wTgoalEE_eigen = wTgoalEE_eigen;
104  robInfo.transforms.wTgoalTool_eigen = wTgoalTool_eigen;
105  robInfo.robotState.vehicleVel.resize(VEHICLE_DOF);
106  std::fill(robInfo.robotState.vehicleVel.begin(), robInfo.robotState.vehicleVel.end(), 0);
107 
108 
110  RobotInterface robotInterface(nh, robotName);
111  robotInterface.init();
112 
113  WorldInterface worldInterface(robotName);
114  worldInterface.waitReady("world", otherRobotName);
115 
117  robotInterface.getJointState(&(robInfo.robotState.jState));
118  robotInterface.getwTv(&(robInfo.robotState.wTv_eigen));
119 
120  worldInterface.getwPos(&(robInfo.exchangedInfo.otherRobPos), otherRobotName);
121 
122  //DEBUGG
123  //robotInterface.getwTjoints(&(robInfo.robotState.wTjoints));
124 
125 
127  std::string filenamePeg; //the model of robot with a "fake joint" in the peg
128  //so, it is ONLY for the already grasped scene
129  if (robotName.compare("g500_A") == 0){
130  filenamePeg = "/home/tori/UWsim/Peg/model/g500ARM5APeg2.urdf";
131  } else {
132  filenamePeg = "/home/tori/UWsim/Peg/model/g500ARM5BPeg2.urdf";
133  }
134  std::string vehicle = "base_link";
135  std::string link0 = "part0";
136  std::string endEffector = "end_effector";
137  std::string peg = "peg";
138  std::string pegHead = "pegHead";
139 
140  KDLHelper kdlHelper(filenamePeg, link0, endEffector, vehicle);
141  //KDLHelper kdlHelper(filenamePeg, link0, endEffector, "");
142  // KDL parse for fixed things (e.g. vehicle and one of his sensor)
143  //TODO Maybe exist an easier method to parse fixed frame from urdf without needed of kdl solver
144  kdlHelper.getFixedFrame(vehicle, link0, &(robInfo.robotStruct.vTlink0));
145  // TODO vT0 non serve più?
146  //kdlHelper.getFixedFrame(endEffector, peg, &(robInfo.robotStruct.eeTtool));
147  kdlHelper.getFixedFrame(endEffector, pegHead, &(robInfo.robotStruct.eeTtoolTip));
148  //TODO TRY : for B is not really fixed...
149 
150 
151  kdlHelper.setEESolvers();
152  //get ee pose RESPECT LINK 0
153  kdlHelper.getEEpose(robInfo.robotState.jState, &(robInfo.robotState.link0Tee_eigen));
154  // useful have vTee: even if it is redunant, everyone use it a lot
155  robInfo.robotState.vTee_eigen = robInfo.robotStruct.vTlink0 * robInfo.robotState.link0Tee_eigen;
156  // get jacobian respect link0
157  kdlHelper.getJacobianEE(robInfo.robotState.jState, &(robInfo.robotState.link0_Jee_man));
158  //get whole jacobian (arm+vehcile and projected on world
159  computeWholeJacobianEE(&robInfo);
160 
161  //kdlHelper.setToolSolvers(robInfo.robotStruct.eeTtool);
162  kdlHelper.setToolSolvers(robInfo.robotStruct.eeTtoolTip);
163 
164  kdlHelper.getJacobianTool(robInfo.robotState.jState, &(robInfo.robotState.v_Jtool_man));
165  computeWholeJacobianTool(&robInfo);
166 
167  robInfo.transforms.wTt_eigen = robInfo.robotState.wTv_eigen *
168  robInfo.robotState.vTee_eigen * robInfo.robotStruct.eeTtoolTip;
169 
170 
171  CoordInterfaceMissMan coordInterface(nh, robotName);
172  VisionInterfaceMissMan visionInterface(nh, robotName);
173 
175  Controller controller(robotName);
176 
178  std::vector<Task*> tasksTPIK1; //the first, non coop, one
179  std::vector<Task*> tasksCoop;
180  std::vector<Task*> tasksArmVehCoord; //for arm-vehicle coord
181  setTaskLists(robotName, &tasksTPIK1, &tasksCoop, &tasksArmVehCoord);
182 
183 
187 
190  Logger logger;
191  if (pathLog.size() > 0){
192  logger = Logger(robotName, pathLog);
193 
194  //to for each list... if task was in a previous list, no problem, folder with same name... overwrite?
195  logger.createTasksListDirectories(tasksTPIK1);
196  logger.createTasksListDirectories(tasksCoop);
197 
198  }
199 
204  //wait coordinator to start
205  double msinit = 1;
206  boost::asio::io_service ioinit;
207  std::cout << "[" << robotName << "][MISSION_MANAGER] Wating for "<<
208  "Coordinator to say I can start...\n";
209  while(!coordInterface.getStartFromCoord()){
210  boost::asio::deadline_timer loopRater(ioinit, boost::posix_time::milliseconds(msinit));
211  coordInterface.pubIamReadyOrNot(true);
212 
213  ros::spinOnce();
214  loopRater.wait();
215  }
216 
217  std::cout << "[" << robotName<< "][MISSION_MANAGER] Start from coordinator "<<
218  "received\n";
219 
220 
224  int ms = MS_CONTROL_LOOP;
225  boost::asio::io_service io;
226  boost::asio::io_service io2;
227 
228  //debug
229  double nLoop = 0.0;
230 
231  while(1){
232 
233  //auto start = std::chrono::steady_clock::now();
234 
235  // this must be inside loop
236  boost::asio::deadline_timer loopRater(io, boost::posix_time::milliseconds(ms));
237 
239  robotInterface.getJointState(&(robInfo.robotState.jState));
240  robotInterface.getwTv(&(robInfo.robotState.wTv_eigen));
241 
242  //TODO TRY : for B is not really fixed...
243 
244  worldInterface.getwPos(&(robInfo.exchangedInfo.otherRobPos), otherRobotName);
245 
247  //visionInterface.getHoleTransform(&(robInfo.transforms.wTholeEstimated_eigen));
248  //DEBUG VISION
249  //std::cout <<"ARRIVED wThole" << robInfo.transforms.wTholeEstimated_eigen << "\n\n";
250  //robInfo.transforms.wTgoalTool_eigen = robInfo.transforms.wTholeEstimated_eigen;
251 
252  //get ee pose RESPECT LINK 0
253  kdlHelper.getEEpose(robInfo.robotState.jState, &(robInfo.robotState.link0Tee_eigen));
254  // useful have vTee: even if it is redunant, tasks use it a lot
255  robInfo.robotState.vTee_eigen = robInfo.robotStruct.vTlink0 * robInfo.robotState.link0Tee_eigen;
256  // get jacobian respect link0
257  kdlHelper.getJacobianEE(robInfo.robotState.jState, &(robInfo.robotState.link0_Jee_man));
258  computeWholeJacobianEE(&robInfo);
259 
260  robInfo.transforms.wTt_eigen = robInfo.robotState.wTv_eigen *
261  robInfo.robotState.vTee_eigen * robInfo.robotStruct.eeTtoolTip;
262  //kdlHelper.setToolSolvers(eeTtool);
263  kdlHelper.getJacobianTool(robInfo.robotState.jState, &(robInfo.robotState.v_Jtool_man));
264  computeWholeJacobianTool(&robInfo);
265 
268  controller.updateMultipleTasksMatrices(tasksTPIK1, &robInfo);
270  std::vector<double> yDotTPIK1 = controller.execAlgorithm(tasksTPIK1);
271 
272  std::vector<double> yDotFinal(TOT_DOF);
273 
275  Eigen::Matrix<double, VEHICLE_DOF, 1> nonCoopCartVel_eigen =
276  robInfo.robotState.w_Jtool_robot * CONV::vector_std2Eigen(yDotTPIK1);
277 
278  Eigen::Matrix<double, VEHICLE_DOF, VEHICLE_DOF> admisVelTool_eigen =
279  robInfo.robotState.w_Jtool_robot * FRM::pseudoInverse(robInfo.robotState.w_Jtool_robot);
280 
281 
282  coordInterface.publishToCoord(nonCoopCartVel_eigen, admisVelTool_eigen);
283 
284  while (coordInterface.getCoopCartVel(&(robInfo.exchangedInfo.coopCartVel)) == 1){ //wait for coopVel to be ready
285  boost::asio::deadline_timer loopRater2(io2, boost::posix_time::milliseconds(1));
286  loopRater2.wait();
287  ros::spinOnce();
288  }
289 
290  controller.updateMultipleTasksMatrices(tasksCoop, &robInfo);
291  std::vector<double> yDotOnlyVeh = controller.execAlgorithm(tasksCoop);
292 
293 
294  controller.updateMultipleTasksMatrices(tasksArmVehCoord, &robInfo);
295  std::vector<double> yDotOnlyArm = controller.execAlgorithm(tasksArmVehCoord);
296 
297  for (int i=0; i<ARM_DOF; i++){
298  yDotFinal.at(i) = yDotOnlyArm.at(i);
299 
300  }
301 
302  for (int i = ARM_DOF; i<TOT_DOF; i++) {
303  yDotFinal.at(i) = yDotOnlyVeh.at(i);
304  //at the moment no error so velocity are exaclty what we are giving
305  robInfo.robotState.vehicleVel.at(i-ARM_DOF) = yDotFinal.at(i);
306  }
307 
311  //robotInterface.sendyDot(yDotTPIK1);
313  //robotInterface.sendyDot(yDotOnlyVeh);
314  robotInterface.sendyDot(yDotFinal);
315 
316 
318  if (pathLog.size() != 0){
319  logger.logAllForTasks(tasksTPIK1);
320  //TODO flag LOGGED to not print same thing twice
321  //or maybe another list with ALL task only to log here and create folder for log
322  //for the moment, yDot are exactly how vehicle and arm are moving
323  logger.logNumbers(yDotTPIK1, "yDotTPIK1");
324  logger.logNumbers(yDotFinal, "yDotFinal");
325  //logger.logNumbers(admisVelTool_eigen, "JJsharp");
326  logger.logNumbers(robInfo.robotState.w_Jtool_robot
327  * CONV::vector_std2Eigen(yDotOnlyVeh), "toolCartVelCoop");
328  }
329 
332 
333 // std::cout << "JJsharp\n" << admisVelTool_eigen << "\n\n";
334 // std::cout << "SENDED non coop vel:\n" << nonCoopCartVel_eigen <<"\n\n\n";
335 // std::cout << "ARRIVED coop vel:\n" << robInfo.exchangedInfo.coopCartVel << "\n\n\n";
336 
337 
338 // std::cout << "J: \n"
339 // << robInfo.robotState.w_Jtool_robot
340 // << "\n\n";
341 // std::cout << "yDot: \n"
342 // << CONV::vector_std2Eigen(yDotOnlyVeh)
343 // << "\n\n";
344 // std::cout << "The tool velocity non coop are (J*yDot): \n"
345 // << nonCoopCartVel_eigen
346 // << "\n\n";
347 // std::cout << "The tool velocity coop are (J*yDot): \n"
348 // << robInfo.robotState.w_Jtool_robot
349 // * CONV::vector_std2Eigen(yDotFinal)
350 // << "\n\n";
351 
352 // std::vector<Task*> tasksDebug = tasksTPIK1;
353 // for(int i=0; i<tasksDebug.size(); i++){
354 // std::cout << "Activation " << tasksDebug[i]->getName() << ": \n";
355 // tasksDebug[i]->getActivation().PrintMtx() ;
356 // std::cout << "\n";
357 // std::cout << "JACOBIAN " << tasksDebug[i]->getName() << ": \n";
358 // tasksDebug[i]->getJacobian().PrintMtx();
359 // std::cout<< "\n";
360 
361 // std::cout << "REFERENCE " << tasksDebug[i]->getName() << ": \n";
362 // tasksDebug[i]->getReference().PrintMtx() ;
363 // std::cout << "\n";
364 // }
365 
366 
367  controller.resetAllUpdatedFlags(tasksTPIK1);
368  controller.resetAllUpdatedFlags(tasksCoop);
369  controller.resetAllUpdatedFlags(tasksArmVehCoord);
370  ros::spinOnce();
371 
372 
373  //auto end = std::chrono::steady_clock::now();
374  //auto duration = std::chrono::duration_cast<std::chrono::milliseconds>( end - start ).count();
375  //std::cout << "TEMPOOOOO "<<duration << "\n\n";
376 
377 
378  loopRater.wait();
379  //nLoop += 1;
380 
381 // if (nLoop > 10){
382 // exit(-1);
383 // }
384 
385  } //end controol loop
386 
387 
388 
389 
390  coordInterface.pubIamReadyOrNot(false);
391 
392  //todo lista con all task per cancellarli
393  deleteTasks(&tasksArmVehCoord);
394 
395  return 0;
396 }
397 
398 
408 void setTaskLists(std::string robotName, std::vector<Task*> *tasks1,
409  std::vector<Task*> *tasksCoord, std::vector<Task*> *tasksArmVeh){
410 
411  bool eqType = true;
412  bool ineqType = false;
413 
414 
416  Task* coopTask6dof = new CoopTask(6, eqType, robotName);
417  Task* coopTask5dof = new CoopTask(5, eqType, robotName);
418  Task* constrainVel = new VehicleConstrainVelTask(6, eqType, robotName);
419 
420 
422  Task* jl = new JointLimitTask(4, ineqType, robotName);
423  Task* ha = new HorizontalAttitudeTask(1, ineqType, robotName);
424  Task* eeAvoid = new ObstacleAvoidEETask(1, ineqType, robotName);
425 
426 
427 
429 
430 
432  Task* pr5 = new PipeReachTask(5, eqType, robotName, ONLYVEH);
433  Task* pr6 = new PipeReachTask(6, eqType, robotName, BOTH);
434 
435  Task* eer = new EndEffectorReachTask(6, eqType, robotName);
436  Task* vehR = new VehicleReachTask(3, eqType, robotName, ANGULAR);
437  Task* vehYaxis = new VehicleReachTask(1, eqType, robotName, YAXIS);
438 
440  Task* shape = new ArmShapeTask(4, ineqType, robotName, PEG_GRASPED_PHASE);
441  //The "fake task" with all eye and zero matrices, needed as last one for algo?
442  Task* last = new LastTask(TOT_DOF, eqType, robotName);
443 
445  // note: order of priority at the moment is here
446  tasks1->push_back(jl);
447  tasks1->push_back(ha);
448  //tasks1->push_back(eeAvoid);
449  tasks1->push_back(pr6);
450  //TODO discutere diff tra pr6 e pr5... il 5 mette più stress sull obj?
451  //tasks1->push_back(vehR);
452  //tasks1->push_back(vehYaxis);
453  //tasks1->push_back(eer);
454  tasks1->push_back(shape);
455  tasks1->push_back(last);
456 
457  //TODO ASK al momento fatte così le versioni 6dof di pr e coop sono
458  //molto meglio
459  //coop 5 dof assolutamente no
460  //pr5 da un po di stress cmq (linearmente -0.034, -0.008, -0.020),
461  //i due tubi divisi si vedono tanto agli estremi
462  //si dovrebbe abbassare gain e saturaz per usare il pr5
463  //soprattutto se c'è sto shape fatto cosi che fa muovere tantissimo
464  //i bracci, è da cambiare lo shape desiderato
465  tasksCoord->push_back(coopTask6dof);
466  tasksCoord->push_back(jl);
467  tasksCoord->push_back(ha);
468  tasksCoord->push_back(pr6);
469  //tasks1->push_back(eeAvoid);
470  tasksCoord->push_back(shape);
471  tasksCoord->push_back(last);
472 
473  tasksArmVeh->push_back(coopTask6dof);
474  tasksArmVeh->push_back(constrainVel);
475  tasksArmVeh->push_back(jl);
476  tasksArmVeh->push_back(ha);
477  tasksArmVeh->push_back(pr6);
478  //tasks1->push_back(eeAvoid);
479 
480  tasksArmVeh->push_back(shape);
481  tasksArmVeh->push_back(last);
482 
483 }
484 
485 
490 void deleteTasks(std::vector<Task*> *tasks){
491  for (std::vector< Task* >::iterator it = tasks->begin() ; it != tasks->end(); ++it)
492  {
493  delete (*it);
494  }
495  tasks->clear();
496 }
497 
498 
499 
500 
501 
502 
503 
504 
505 
506 
507 
508 
509 /********* OLD VERSIONS *********************************************************************************
510 
511 
512 
513 
514 void setTaskLists(std::string robotName, std::vector<Task*> *tasks){
515 
517  // note: order of priority at the moment is here
518  bool eqType = true;
519  bool ineqType = false;
520 
521  //tasks->push_back(new VehicleNullVelTask(6, ineqType));
522 
523  tasks->push_back(new JointLimitTask(4, ineqType, robotName));
524  tasks->push_back(new HorizontalAttitudeTask(1, ineqType, robotName));
525 
526  //tasks->push_back(new ObstacleAvoidEETask(1, ineqType, robotName));
527  //tasks->push_back(new ObstacleAvoidVehicleTask(1, ineqType, robotName));
528 
529  //tasks->push_back(new FovEEToToolTask(1, ineqType, robotName));
530 
531  //tasks->push_back(new EndEffectorReachTask(6, eqType, robotName));
532  tasks->push_back(new PipeReachTask(5, eqType, robotName, BOTH));
533  //tasks->push_back(new VehicleReachTask(6, eqType, robotName));
534 
535  tasks->push_back(new ArmShapeTask(4, ineqType, robotName, MID_LIMITS));
536  //The "fake task" with all eye and zero matrices, needed as last one for algo
537  tasks->push_back(new LastTask(TOT_DOF, eqType, robotName));
538 }
539 
540 void setTaskLists(std::string robotName, std::vector<Task*> *tasks1, std::vector<Task*> *tasksFinal){
541 
542  bool eqType = true;
543  bool ineqType = false;
544 
545 
547  Task* coopTask6dof = new CoopTask(6, eqType, robotName);
548  Task* coopTask5dof = new CoopTask(5, eqType, robotName);
549 
550 
552  Task* jl = new JointLimitTask(4, ineqType, robotName);
553  Task* ha = new HorizontalAttitudeTask(1, ineqType, robotName);
554 
555 
557 
558 
560  Task* pr5 = new PipeReachTask(5, eqType, robotName, BOTH);
561  Task* pr6 = new PipeReachTask(6, eqType, robotName, BOTH);
562 
563  Task* tr = new EndEffectorReachTask(6, eqType, robotName);
564 
566  Task* shape = new ArmShapeTask(4, ineqType, robotName, MID_LIMITS);
567  //The "fake task" with all eye and zero matrices, needed as last one for algo?
568  Task* last = new LastTask(TOT_DOF, eqType, robotName);
569 
571  // note: order of priority at the moment is here
572  tasks1->push_back(jl);
573  tasks1->push_back(ha);
574  tasks1->push_back(pr5);
575  //tasks1->push_back(tr);
576  //tasks1->push_back(shape);
577  tasks1->push_back(last);
578 
579  tasksFinal->push_back(coopTask5dof);
580  // tasksFinal->push_back(jl);
581  //tasksFinal->push_back(ha);
582  //tasksFinal->push_back(shape);
583  tasksFinal->push_back(last);
584 }
585 
586 
587 
588 
589 
590 
592 // std::cout << "JACOBIAN " << i << ": \n";
593 // tasks[i]->getJacobian().PrintMtx();
594 // std::cout<< "\n";
595 // std::cout << "REFERENCE " << i << ": \n";
596 // tasks[i]->getReference().PrintMtx() ;
597 // std::cout << "\n";
598 
599 
600 //std::cout << nonCoopCartVel_eigen << "\n\n";
601 //std::cout << admisVelTool_eigen << "\n\n";
602 
603 
604 //Q.PrintMtx("Q"); ///DEBUG
605 //yDot_cmat.PrintMtx("yDot");
606 
607 
608 
609 //DEBUGGGG
610 //computeJacobianToolNoKdl(&robInfo, robotName);
611 
612 //std::cout << "con KDL:\n" << robInfo.robotState.w_Jtool_robot << "\n\n";
613 //std::cout << "senza KDL:\n" << robInfo.robotState.w_JNoKdltool_robot << "\n\n";
614 
615 /*
616 //debug
617 Eigen::Matrix4d toolPose_eigen;
618 kdlHelper.getToolpose(robInfo.robotState.jState, eeTtool, &toolPose_eigen);
619 Eigen::Matrix4d W_toolPose_eigen = robInfo.robotState.wTv_eigen * robInfo.robotStruct.vTlink0 * toolPose_eigen;
620 
621 std::cout << "ToolPOSE\n" <<
622  W_toolPose_eigen << "\n\n";
623 */
Definition: logger.h:16
The Controller class is responsabile of 1) taking matrices and giving them to Tasks classes...
Definition: controller.h:20
std::vector< double > vehicleVel
vehicle and joint
Definition: infos.h:45
robotInterface: a ros node responsible of taken info from simulator and robot sensors, and of given commands back. It is the intermiate layer between actual robot and mission manager ("main")
"Fake" Task needed as last to algorithm, it has all fixed matrices of eye and zeros so no setxx are n...
Definition: lastTask.h:9
The ObstacleAvoidEETask class Usage of this task can be for avoiding with the end effector...
The CoopTask class.
Definition: coopTask.h:10
The vehicleConstrainVelTask class This task is a non-reactive one used to to constrain the velocities...
The CoordInterface class class to deal with ros comunications (pub/sub) from MissionManager node to C...
Task to make the end effector reach a goal (both linear and angular position)
Task to make the vehicle reach a goal (both linear and angular position)
The WorldInterface class to get position from world to anything else.
Eigen::Matrix< double, 6, ARM_DOF > link0_Jee_man
Jacobians.
Definition: infos.h:52
Definition: infos.h:117
Eigen::Matrix4d wTv_eigen
Transforms.
Definition: infos.h:34
The ArmShapeTask class Preferred arm Shape: an optimization task. It is a non scalar task...
Definition: armShapeTask.h:20
ABSTRACT class task. Each task is a derived class of this class. It contains all the variable that th...
Definition: task.h:17