Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include <schunk_powercube_chain/PowerCubeSim.h>
00019 #include <string>
00020 #include <sstream>
00021 #ifdef PYTHON_THREAD
00022 #include <Python.h>
00023 #endif
00024
00025
00026 #define DEG 57.295779524
00027 #define MANUAL_AXES0_OFFSET 1.8
00028 #define MANUAL_AXES6_OFFSET 1.5
00029
00030 #define SIM_CLOCK_FREQUENCY 10.0 // ms
00031 using namespace std;
00032
00033 #ifndef PCTRL_CHECK_INITIALIZED()
00034 #define PCTRL_CHECK_INITIALIZED() \
00035 if (isInitialized() == false) \
00036 { \
00037 m_ErrorMessage.assign("Manipulator not initialized."); \
00038 return false; \
00039 }
00040 #endif
00041
00042 PowerCubeSim::PowerCubeSim()
00043 {
00044 m_Dev = 0;
00045 m_NumOfModules = 0;
00046 m_SimThreadArgs = NULL;
00047 m_SimThreadID = NULL;
00048
00049
00050 }
00051
00058 bool PowerCubeSim::Init(PowerCubeCtrlParams* params)
00059 {
00060
00061 m_DOF = params->GetNumberOfDOF();
00062
00063 m_Dev = 0;
00064 m_NumOfModules = m_DOF;
00065
00066 m_maxVel = params->GetMaxVel();
00067 m_maxAcc = params->GetMaxAcc();
00068
00069
00070 m_IdModules.clear();
00071
00072 m_CurrentAngles.resize(m_DOF);
00073 m_CurrentAngularMaxAccel.resize(m_DOF);
00074 m_CurrentAngularMaxVel.resize(m_DOF);
00075 m_CurrentAngularVel.resize(m_DOF);
00076
00077
00078
00079 for (int i = 0; i < m_DOF; i++)
00080 {
00081 std::ostringstream os;
00082 os << "ID_Module_Number" << i + 1;
00083
00084
00085
00086
00087 m_CurrentAngles[i] = 0.0;
00088 m_CurrentAngularVel[i] = 0.0;
00089 m_CurrentAngularMaxVel[i] = m_maxVel[i];
00090 m_CurrentAngularMaxAccel[i] = m_maxAcc[i];
00091
00092
00093 }
00094
00095
00096
00097
00098
00099
00100 pthread_mutex_init(&m_Movement_Mutex, NULL);
00101 pthread_mutex_init(&m_Angles_Mutex, NULL);
00102 pthread_mutex_init(&m_AngularVel_Mutex, NULL);
00103
00104 m_SimThreadID = (pthread_t*)malloc(m_DOF * sizeof(pthread_t));
00105 m_MovementInProgress.resize(m_DOF);
00106 m_SimThreadArgs = (SimThreadArgs**)malloc(m_DOF * sizeof(SimThreadArgs*));
00107 for (int i = 0; i < m_DOF; i++)
00108 {
00109 m_MovementInProgress[i] = false;
00110 m_SimThreadArgs[i] = new SimThreadArgs();
00111 m_SimThreadArgs[i]->cubeSimPtr = this;
00112 m_SimThreadArgs[i]->cubeID = i;
00113 }
00114 setMaxVelocity(MAX_VEL);
00115 setMaxAcceleration(MAX_ACC);
00116
00117
00118 m_Initialized = true;
00119 return true;
00120 }
00121
00124 PowerCubeSim::~PowerCubeSim()
00125 {
00126 free(m_SimThreadID);
00127 for (int i = 0; i < m_DOF; i++)
00128 {
00129 delete m_SimThreadArgs[i];
00130 }
00131 free(m_SimThreadArgs);
00132 }
00133
00135 bool PowerCubeSim::getConfig(std::vector<double>& result)
00136 {
00137 PCTRL_CHECK_INITIALIZED();
00138
00139
00140
00141 pthread_mutex_lock(&m_Angles_Mutex);
00142
00143 result.resize(m_DOF);
00144 for (int i; i < m_DOF; i++)
00145 result[i] = m_CurrentAngles[i] * DEG;
00146
00147
00148
00149 pthread_mutex_unlock(&m_Angles_Mutex);
00150
00151
00152 return true;
00153 }
00154
00156 bool PowerCubeSim::getJointVelocities(std::vector<double>& result)
00157 {
00158 PCTRL_CHECK_INITIALIZED();
00159
00160
00161
00162 pthread_mutex_lock(&m_AngularVel_Mutex);
00163
00164 result.resize(m_DOF);
00165 result = m_CurrentAngularVel;
00166
00167
00168
00169 pthread_mutex_unlock(&m_AngularVel_Mutex);
00170
00171
00172 return true;
00173 }
00174 void PowerCubeSim::setCurrentAngles(std::vector<double> Angles)
00175 {
00176
00177
00178 pthread_mutex_lock(&m_Angles_Mutex);
00179
00180
00181 m_CurrentAngles = Angles;
00182
00183
00184
00185 pthread_mutex_unlock(&m_Angles_Mutex);
00186
00187 }
00188
00189 void PowerCubeSim::setCurrentJointVelocities(std::vector<double> AngularVel)
00190 {
00191
00192
00193 pthread_mutex_lock(&m_AngularVel_Mutex);
00194
00195
00196 m_CurrentAngularVel = AngularVel;
00197
00198
00199
00200 pthread_mutex_unlock(&m_AngularVel_Mutex);
00201
00202 }
00203
00205 bool PowerCubeSim::MoveJointSpaceSync(const std::vector<double>& target)
00206 {
00207 PCTRL_CHECK_INITIALIZED();
00208 std::cout << "Starting MoveJointSpaceSync(Jointd Angle) ... " << endl;
00209 std::vector<double> targetRAD;
00210 targetRAD.resize(m_DOF);
00211 for (int i = 0; i < m_DOF; i++)
00212 targetRAD[i] = target[i] / DEG;
00213
00214
00215 std::vector<double> acc(m_DOF);
00216 std::vector<double> vel(m_DOF);
00217
00218 double TG = 0;
00219
00220 try
00221 {
00222
00223 int DOF = m_DOF;
00224
00225 std::vector<double> posnow;
00226 if (getConfig(posnow) == false)
00227 return false;
00228
00229 std::vector<double> velnow;
00230 if (getJointVelocities(velnow) == false)
00231 return false;
00232
00233 std::vector<double> times(DOF);
00234
00235 for (int i = 0; i < DOF; i++)
00236 {
00237 RampCommand rm(posnow[i], velnow[i], targetRAD[i], m_maxAcc[i], m_maxVel[i]);
00238 times[i] = rm.getTotalTime();
00239 }
00240
00241
00242 int furthest = 0;
00243
00244 double max = times[0];
00245
00246 for (int i = 1; i < m_DOF; i++)
00247 {
00248 if (times[i] > max)
00249 {
00250 max = times[i];
00251 furthest = i;
00252 }
00253 }
00254
00255 RampCommand rm_furthest(posnow[furthest], velnow[furthest], targetRAD[furthest], m_maxAcc[furthest],
00256 m_maxVel[furthest]);
00257
00258 double T1 = rm_furthest.T1();
00259 double T2 = rm_furthest.T2();
00260 double T3 = rm_furthest.T3();
00261
00262
00263 TG = T1 + T2 + T3;
00264
00265
00266 acc[furthest] = m_maxAcc[furthest];
00267 vel[furthest] = m_maxVel[furthest];
00268
00269 for (int i = 0; i < DOF; i++)
00270 {
00271 if (i != furthest)
00272 {
00273 double a;
00274 double v;
00275
00276 RampCommand::calculateAV(posnow[i], velnow[i], targetRAD[i], TG, T3, m_maxAcc[i], m_maxVel[i], a, v);
00277
00278 acc[i] = a;
00279 vel[i] = v;
00280 }
00281 }
00282 }
00283 catch (...)
00284 {
00285 return false;
00286 }
00287
00288 startSimulatedMovement(targetRAD);
00289
00290
00291 return true;
00292 }
00293
00296 double PowerCubeSim::timeRampMove(double dtheta, double vnow, double v, double a)
00297 {
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307 double vm = (dtheta < 0) ? -v : v;
00308 double am = (dtheta < 0) ? -a : a;
00309
00310
00311
00312
00313 double T1 = (vm - vnow) / am;
00314
00315 double dtheta1 = vnow * T1 + 0.5 * am * T1 * T1;
00316
00317
00318
00319
00320 double T3 = vm / am;
00321
00322 double dtheta3 = 0.5 * vm * T3;
00323
00324
00325 double dtheta2 = dtheta - dtheta1 - dtheta3;
00326
00327 double T2 = dtheta2 / vm;
00328
00329
00330
00331
00332
00333
00334 return T1 + T2 + T3;
00335 }
00336
00338 bool PowerCubeSim::MoveVel(const std::vector<double>& vel)
00339 {
00340 PCTRL_CHECK_INITIALIZED();
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353 }
00354
00356 bool PowerCubeSim::Stop()
00357 {
00358 for (int i = 0; i < m_DOF; i++)
00359 setStatusMoving(i, false);
00360 return true;
00361 }
00362
00365 bool PowerCubeSim::setMaxVelocity(double radpersec)
00366 {
00367 for (int i = 0; i < m_DOF; i++)
00368 {
00369 m_CurrentAngularMaxVel[i] = radpersec;
00370 }
00371 return true;
00372 }
00373
00374 bool PowerCubeSim::setMaxVelocity(const std::vector<double>& radpersec)
00375 {
00376 for (int i = 0; i < m_DOF; i++)
00377 {
00378 m_CurrentAngularMaxVel[i] = radpersec[i];
00379 }
00380 return true;
00381 }
00382
00385 bool PowerCubeSim::setMaxAcceleration(double radPerSecSquared)
00386 {
00387 PCTRL_CHECK_INITIALIZED();
00388
00389 for (int i = 0; i < m_DOF; i++)
00390 {
00391 m_CurrentAngularMaxAccel[i] = radPerSecSquared;
00392 }
00393
00394 return true;
00395 }
00396 bool PowerCubeSim::setMaxAcceleration(const std::vector<double>& radPerSecSquared)
00397 {
00398 PCTRL_CHECK_INITIALIZED();
00399
00400 for (int i = 0; i < m_DOF; i++)
00401 {
00402 m_CurrentAngularMaxAccel[i] = radPerSecSquared[i];
00403 }
00404
00405 return true;
00406 }
00407
00409 bool PowerCubeSim::statusMoving()
00410 {
00411 PCTRL_CHECK_INITIALIZED();
00412 bool isMoving = false;
00413
00414
00415 pthread_mutex_lock(&m_Movement_Mutex);
00416
00417 for (int i = 0; i < m_DOF; i++)
00418 {
00419 if (m_MovementInProgress[i])
00420 {
00421 isMoving = true;
00422 break;
00423 }
00424 }
00425
00426
00427
00428 pthread_mutex_unlock(&m_Movement_Mutex);
00429
00430
00431 return isMoving;
00432 }
00433
00434 bool PowerCubeSim::statusMoving(int cubeNo)
00435 {
00436 PCTRL_CHECK_INITIALIZED();
00437 bool isMoving = false;
00438
00439
00440 pthread_mutex_lock(&m_Movement_Mutex);
00441
00442 if (m_MovementInProgress[cubeNo])
00443 {
00444 isMoving = true;
00445 }
00446
00447
00448
00449 pthread_mutex_unlock(&m_Movement_Mutex);
00450
00451
00452 return isMoving;
00453 }
00454
00455 void PowerCubeSim::setStatusMoving(int cubeNo, bool moving)
00456 {
00457
00458 pthread_mutex_lock(&m_Movement_Mutex);
00459
00460
00461 m_MovementInProgress[cubeNo] = moving;
00462
00463
00464 pthread_mutex_unlock(&m_Movement_Mutex);
00465
00466 }
00467
00469 bool PowerCubeSim::statusDec()
00470 {
00471 PCTRL_CHECK_INITIALIZED();
00472
00473
00474
00475
00476
00477
00478
00479
00480
00481 return false;
00482 }
00483
00485 bool PowerCubeSim::statusAcc()
00486 {
00487 PCTRL_CHECK_INITIALIZED();
00488
00489
00490
00491
00492
00493
00494
00495
00496
00497
00498 return false;
00499 }
00500
00501 void* SimThreadRoutine(void* threadArgs)
00502 {
00503
00504 SimThreadArgs* args = (SimThreadArgs*)threadArgs;
00505 PowerCubeSim* cubeSimPtr = args->cubeSimPtr;
00506 int cubeNo = args->cubeID;
00507 double targetAngle = args->targetAngle;
00508
00509
00510
00511
00512 float t1, t2, t, tges;
00513 double deltaT = SIM_CLOCK_FREQUENCY / 1000;
00514 t1 = t2 = t = tges = 0;
00515 float maxVel = (cubeSimPtr->getCurrentAngularMaxVel())[cubeNo];
00516 float maxAccel = (cubeSimPtr->getCurrentAngularMaxAccel())[cubeNo];
00517 std::vector<double> currAngles;
00518 cubeSimPtr->getConfig(currAngles);
00519 std::vector<double> currVels;
00520 cubeSimPtr->getJointVelocities(currVels);
00521
00522 double deltaAngle = targetAngle - currAngles[cubeNo];
00523
00524
00525 t1 = maxVel / maxAccel;
00526
00527
00528 t2 = abs(deltaAngle) / maxVel - t1;
00529
00530
00531
00532
00533
00534 if (abs(deltaAngle) > maxVel * maxVel / maxAccel)
00535 {
00536 tges = 2 * t1 + t2;
00537 }
00538 else
00539 {
00540
00541 t = sqrt(abs(deltaAngle) / (maxAccel));
00542
00543
00544 tges = 2 * t;
00545 }
00546
00547
00548 if (deltaAngle < 0)
00549 {
00550 maxAccel = -maxAccel;
00551 maxVel = -maxVel;
00552 }
00553 std::cout << "maxVel: " << maxVel << "; maxAccel: " << maxAccel << "; t1 [ms]: " << t1 << "; t2 [ms]: " << t2
00554 << "; deltaAngle[rad]" << deltaAngle << endl;
00555
00556
00557
00558 double simulatedTime = 0.0;
00559 int n = 0;
00560 float currDeltaAngle = deltaAngle;
00561
00562 if (abs(deltaAngle) > 0.001)
00563 {
00564 while ((simulatedTime <= tges) && cubeSimPtr->getStatusMoving(cubeNo) )
00565
00566 {
00567
00568 cubeSimPtr->millisleep((int)SIM_CLOCK_FREQUENCY);
00569 simulatedTime += SIM_CLOCK_FREQUENCY / 1000;
00570 n++;
00571 cubeSimPtr->getJointVelocities(currVels);
00572
00573 double deltaPhi = 0.0;
00574
00575
00576 if (abs(deltaAngle) > maxVel * maxVel / abs(maxAccel))
00577 {
00578 if (simulatedTime < t1)
00579 {
00580 deltaPhi = 0.5 * maxAccel * (n * deltaT * n * deltaT - (n - 1) * deltaT * (n - 1) * deltaT);
00581 currVels[cubeNo] = maxAccel * n * deltaT;
00582 std::cout << "Phase 1, maxVel ->";
00583 }
00584 else if ((t1 < simulatedTime) && (simulatedTime < t1 + t2))
00585 {
00586 deltaPhi = maxVel * deltaT;
00587 currVels[cubeNo] = maxVel;
00588 std::cout << "Phase 2, maxVel ->";
00589 }
00590 else if ((simulatedTime > t1 + t2) && (simulatedTime < 2 * t1 + t2))
00591 {
00592
00593 deltaPhi = maxVel * deltaT -
00594 0.5 * maxAccel * ((n * deltaT - (t1 + t2)) * (n * deltaT - (t1 + t2)) -
00595 ((n - 1) * deltaT - (t1 + t2)) * ((n - 1) * deltaT - (t1 + t2)));
00596 currVels[cubeNo] = maxVel - maxAccel * (simulatedTime - (t1 + t2));
00597 std::cout << "Phase 3, maxVel ->";
00598 }
00599 else
00600 {
00601 deltaPhi = 0.0;
00602 currVels[cubeNo] = 0.0;
00603 std::cout << "Phase 4, maxVel ->";
00604 }
00605 }
00606
00607 else
00608 {
00609 if (simulatedTime < t)
00610 {
00611
00612 deltaPhi = 0.5 * maxAccel * (n * deltaT * n * deltaT - (n - 1) * deltaT * (n - 1) * deltaT);
00613 currVels[cubeNo] = maxAccel * simulatedTime;
00614 std::cout << "Phase 1 ->";
00615 }
00616 else if ((simulatedTime > t) && (simulatedTime <= 2 * t))
00617 {
00618
00619 deltaPhi = maxAccel * t * deltaT - 0.5 * maxAccel * ((n * deltaT - t) * (n * deltaT - t) - ((n - 1) * deltaT - t) * ((n - 1) * deltaT - t));
00620 currVels[cubeNo] = maxAccel * t - maxAccel * (simulatedTime - t);
00621 std::cout << "Phase 2 ->";
00622 }
00623 else
00624 {
00625 deltaPhi = 0.0;
00626 currVels[cubeNo] = 0.0;
00627 std::cout << "Phase 3 ->" << t << "\n";
00628 }
00629 }
00630 cubeSimPtr->getConfig(currAngles);
00631
00632 currAngles[cubeNo] = currAngles[cubeNo] + deltaPhi;
00633 currDeltaAngle = targetAngle - currAngles[cubeNo];
00634
00635
00636
00637
00638 cubeSimPtr->setCurrentAngles(currAngles);
00639 cubeSimPtr->setCurrentJointVelocities(currVels);
00640 }
00641 }
00642
00643
00644 cubeSimPtr->setStatusMoving(cubeNo, false);
00645 currVels[cubeNo] = 0.0;
00646 cubeSimPtr->setCurrentJointVelocities(currVels);
00647
00648
00649 pthread_exit(NULL);
00650 }
00651
00652 int PowerCubeSim::startSimulatedMovement(std::vector<double> target)
00653 {
00654 if (statusMoving())
00655 {
00656 std::cout << "startSimulatedMovement: Movement already in progress, preemption not implemented yet! Aborting .."
00657 << endl;
00658 }
00659 else
00660 {
00661
00662
00663 for (int i = 0; i < m_DOF; i++)
00664 {
00665 setStatusMoving(i, true);
00666 m_SimThreadArgs[i]->targetAngle = target[i];
00667 pthread_create(&m_SimThreadID[i], NULL, SimThreadRoutine, (void*)m_SimThreadArgs[i]);
00668 }
00669 }
00670 return 0;
00671 }
00672 void PowerCubeSim::millisleep(unsigned int milliseconds) const
00673 {
00674 timespec warten;
00675
00676 warten.tv_sec = milliseconds / 1000;
00677 warten.tv_nsec = (milliseconds % 1000) * 1000000;
00678 timespec gewartet;
00679 nanosleep(&warten, &gewartet);
00680 }
00681
00684
00685
00686
00687
00688
00689
00690
00691
00692
00693
00694
00695
00696
00697
00698
00699
00700
00701
00702
00703
00704
00705
00706
00707
00708
00709
00710
00711
00712
00713
00714
00715
00716
00717
00718
00719
00720
00721
00722
00723
00724
00725
00726
00727
00728
00729
00730
00731
00732
00733
00734
00735
00736
00737
00738
00739
00740
00741
00742
00743
00744
00745
00746
00747
00748
00749
00750
00751
00752
00753
00754
00755
00756
00757
00758
00759
00760
00761
00762
00763
00764
00765
00766
00767
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777
00778
00779
00780
00781
00782