1 #include "header/missionManager.h" 17 int main(
int argc,
char **argv)
20 std::cout <<
"[MISSION_MANAGER] Please insert the two robots name"<< std::endl;
23 std::string robotName = argv[1];
24 std::string otherRobotName = argv[2];
26 if (LOG && (argc > 3)){
32 ros::init(argc, argv, robotName +
"_MissionManager");
33 std::cout <<
"[" << robotName <<
"][MISSION_MANAGER] Start" << std::endl;
42 double goalLinearVect[] = {-0.287, -0.090, 8};
44 Eigen::Matrix4d wTgoalVeh_eigen = Eigen::Matrix4d::Identity();
46 wTgoalVeh_eigen.topLeftCorner(3,3) = Eigen::Matrix3d::Identity();
48 wTgoalVeh_eigen(0, 3) = goalLinearVect[0];
49 wTgoalVeh_eigen(1, 3) = goalLinearVect[1];
50 wTgoalVeh_eigen(2, 3) = goalLinearVect[2];
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;
60 goalLinearVectEE[0] = -1.11;
61 goalLinearVectEE[1] = -0.090;
62 goalLinearVectEE[2] = 9.594;
64 Eigen::Matrix4d wTgoalEE_eigen = Eigen::Matrix4d::Identity();
68 wTgoalEE_eigen.topLeftCorner(3,3) << 0, -1, 0,
72 wTgoalEE_eigen(0, 3) = goalLinearVectEE[0];
73 wTgoalEE_eigen(1, 3) = goalLinearVectEE[1];
74 wTgoalEE_eigen(2, 3) = goalLinearVectEE[2];
78 double goalLinearVectTool[] = {-0.20, -3.102, 9.000};
80 Eigen::Matrix4d wTgoalTool_eigen = Eigen::Matrix4d::Identity();
83 wTgoalTool_eigen.topLeftCorner<3,3>() << 0, 1, 0,
90 wTgoalTool_eigen(0, 3) = goalLinearVectTool[0];
91 wTgoalTool_eigen(1, 3) = goalLinearVectTool[1];
92 wTgoalTool_eigen(2, 3) = goalLinearVectTool[2];
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);
111 robotInterface.init();
114 worldInterface.waitReady(
"world", otherRobotName);
117 robotInterface.getJointState(&(robInfo.robotState.jState));
118 robotInterface.getwTv(&(robInfo.robotState.
wTv_eigen));
120 worldInterface.getwPos(&(robInfo.exchangedInfo.otherRobPos), otherRobotName);
127 std::string filenamePeg;
129 if (robotName.compare(
"g500_A") == 0){
130 filenamePeg =
"/home/tori/UWsim/Peg/model/g500ARM5APeg2.urdf";
132 filenamePeg =
"/home/tori/UWsim/Peg/model/g500ARM5BPeg2.urdf";
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";
140 KDLHelper kdlHelper(filenamePeg, link0, endEffector, vehicle);
144 kdlHelper.getFixedFrame(vehicle, link0, &(robInfo.robotStruct.vTlink0));
147 kdlHelper.getFixedFrame(endEffector, pegHead, &(robInfo.robotStruct.eeTtoolTip));
151 kdlHelper.setEESolvers();
153 kdlHelper.getEEpose(robInfo.robotState.jState, &(robInfo.robotState.link0Tee_eigen));
155 robInfo.robotState.vTee_eigen = robInfo.robotStruct.vTlink0 * robInfo.robotState.link0Tee_eigen;
157 kdlHelper.getJacobianEE(robInfo.robotState.jState, &(robInfo.robotState.
link0_Jee_man));
159 computeWholeJacobianEE(&robInfo);
162 kdlHelper.setToolSolvers(robInfo.robotStruct.eeTtoolTip);
164 kdlHelper.getJacobianTool(robInfo.robotState.jState, &(robInfo.robotState.v_Jtool_man));
165 computeWholeJacobianTool(&robInfo);
167 robInfo.transforms.wTt_eigen = robInfo.robotState.
wTv_eigen *
168 robInfo.robotState.vTee_eigen * robInfo.robotStruct.eeTtoolTip;
172 VisionInterfaceMissMan visionInterface(nh, robotName);
178 std::vector<Task*> tasksTPIK1;
179 std::vector<Task*> tasksCoop;
180 std::vector<Task*> tasksArmVehCoord;
181 setTaskLists(robotName, &tasksTPIK1, &tasksCoop, &tasksArmVehCoord);
191 if (pathLog.size() > 0){
192 logger =
Logger(robotName, pathLog);
195 logger.createTasksListDirectories(tasksTPIK1);
196 logger.createTasksListDirectories(tasksCoop);
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);
217 std::cout <<
"[" << robotName<<
"][MISSION_MANAGER] Start from coordinator "<<
224 int ms = MS_CONTROL_LOOP;
225 boost::asio::io_service io;
226 boost::asio::io_service io2;
236 boost::asio::deadline_timer loopRater(io, boost::posix_time::milliseconds(ms));
239 robotInterface.getJointState(&(robInfo.robotState.jState));
240 robotInterface.getwTv(&(robInfo.robotState.
wTv_eigen));
244 worldInterface.getwPos(&(robInfo.exchangedInfo.otherRobPos), otherRobotName);
253 kdlHelper.getEEpose(robInfo.robotState.jState, &(robInfo.robotState.link0Tee_eigen));
255 robInfo.robotState.vTee_eigen = robInfo.robotStruct.vTlink0 * robInfo.robotState.link0Tee_eigen;
257 kdlHelper.getJacobianEE(robInfo.robotState.jState, &(robInfo.robotState.
link0_Jee_man));
258 computeWholeJacobianEE(&robInfo);
260 robInfo.transforms.wTt_eigen = robInfo.robotState.
wTv_eigen *
261 robInfo.robotState.vTee_eigen * robInfo.robotStruct.eeTtoolTip;
263 kdlHelper.getJacobianTool(robInfo.robotState.jState, &(robInfo.robotState.v_Jtool_man));
264 computeWholeJacobianTool(&robInfo);
268 controller.updateMultipleTasksMatrices(tasksTPIK1, &robInfo);
270 std::vector<double> yDotTPIK1 = controller.execAlgorithm(tasksTPIK1);
272 std::vector<double> yDotFinal(TOT_DOF);
275 Eigen::Matrix<double, VEHICLE_DOF, 1> nonCoopCartVel_eigen =
276 robInfo.robotState.w_Jtool_robot * CONV::vector_std2Eigen(yDotTPIK1);
278 Eigen::Matrix<double, VEHICLE_DOF, VEHICLE_DOF> admisVelTool_eigen =
279 robInfo.robotState.w_Jtool_robot * FRM::pseudoInverse(robInfo.robotState.w_Jtool_robot);
282 coordInterface.publishToCoord(nonCoopCartVel_eigen, admisVelTool_eigen);
284 while (coordInterface.getCoopCartVel(&(robInfo.exchangedInfo.coopCartVel)) == 1){
285 boost::asio::deadline_timer loopRater2(io2, boost::posix_time::milliseconds(1));
290 controller.updateMultipleTasksMatrices(tasksCoop, &robInfo);
291 std::vector<double> yDotOnlyVeh = controller.execAlgorithm(tasksCoop);
294 controller.updateMultipleTasksMatrices(tasksArmVehCoord, &robInfo);
295 std::vector<double> yDotOnlyArm = controller.execAlgorithm(tasksArmVehCoord);
297 for (
int i=0; i<ARM_DOF; i++){
298 yDotFinal.at(i) = yDotOnlyArm.at(i);
302 for (
int i = ARM_DOF; i<TOT_DOF; i++) {
303 yDotFinal.at(i) = yDotOnlyVeh.at(i);
305 robInfo.robotState.
vehicleVel.at(i-ARM_DOF) = yDotFinal.at(i);
314 robotInterface.sendyDot(yDotFinal);
318 if (pathLog.size() != 0){
319 logger.logAllForTasks(tasksTPIK1);
323 logger.logNumbers(yDotTPIK1,
"yDotTPIK1");
324 logger.logNumbers(yDotFinal,
"yDotFinal");
326 logger.logNumbers(robInfo.robotState.w_Jtool_robot
327 * CONV::vector_std2Eigen(yDotOnlyVeh),
"toolCartVelCoop");
367 controller.resetAllUpdatedFlags(tasksTPIK1);
368 controller.resetAllUpdatedFlags(tasksCoop);
369 controller.resetAllUpdatedFlags(tasksArmVehCoord);
390 coordInterface.pubIamReadyOrNot(
false);
393 deleteTasks(&tasksArmVehCoord);
408 void setTaskLists(std::string robotName, std::vector<Task*> *tasks1,
409 std::vector<Task*> *tasksCoord, std::vector<Task*> *tasksArmVeh){
412 bool ineqType =
false;
416 Task* coopTask6dof =
new CoopTask(6, eqType, robotName);
417 Task* coopTask5dof =
new CoopTask(5, eqType, robotName);
446 tasks1->push_back(jl);
447 tasks1->push_back(ha);
449 tasks1->push_back(pr6);
454 tasks1->push_back(shape);
455 tasks1->push_back(last);
465 tasksCoord->push_back(coopTask6dof);
466 tasksCoord->push_back(jl);
467 tasksCoord->push_back(ha);
468 tasksCoord->push_back(pr6);
470 tasksCoord->push_back(shape);
471 tasksCoord->push_back(last);
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);
480 tasksArmVeh->push_back(shape);
481 tasksArmVeh->push_back(last);
490 void deleteTasks(std::vector<Task*> *tasks){
491 for (std::vector< Task* >::iterator it = tasks->begin() ; it != tasks->end(); ++it)
The Controller class is responsabile of 1) taking matrices and giving them to Tasks classes...
std::vector< double > vehicleVel
vehicle and joint
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...
The ObstacleAvoidEETask class Usage of this task can be for avoiding with the end effector...
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.
Eigen::Matrix4d wTv_eigen
Transforms.
The ArmShapeTask class Preferred arm Shape: an optimization task. It is a non scalar task...
ABSTRACT class task. Each task is a derived class of this class. It contains all the variable that th...