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