PowerCubeSim.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
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 //#define __LINUX__
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   // pthreads variables
00050 }
00051 
00058 bool PowerCubeSim::Init(PowerCubeCtrlParams* params)
00059 {
00060   // std::cout << "---------- PowerCubes-Simulation Init -------------" << std::endl;
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   // Make sure m_IdModules is clear of Elements:
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   // m_AngleOffsets = m_Obj_Manipulator->GetThetaOffsets();
00078 
00079   for (int i = 0; i < m_DOF; i++)
00080   {
00081     std::ostringstream os;
00082     os << "ID_Module_Number" << i + 1;
00083 
00084     // Get the Module Id from the config file
00085 
00086     // set initial angles to zero
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     // printf("Offset Angle %d: %f\n",i,m_AngleOffsets[i]);
00093   }
00094 
00095   // Jetzt Winkelgrenzen setzen:
00096   // m_AngleLimits = m_Obj_Manipulator->GetLimitsTheta();
00097 
00098   // pthreads initialisation
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   // std::cout << "---------- PowerCubes Init fertig ----------" << std::endl;
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   // lock mutex
00139   //
00140   // std::cout << "getConfig: Waiting for Current_Angles_Mutex ... ";
00141   pthread_mutex_lock(&m_Angles_Mutex);
00142   // m_Out << "locked"<<endl;
00143   result.resize(m_DOF);
00144   for (int i; i < m_DOF; i++)
00145     result[i] = m_CurrentAngles[i] * DEG;
00146   // unlock mutex
00147   //
00148   // m_Out <<"getConfig: Unlocking Angles_Mutex ... ";
00149   pthread_mutex_unlock(&m_Angles_Mutex);
00150   // m_Out <<"unlocked "<<endl;
00151 
00152   return true;
00153 }
00154 
00156 bool PowerCubeSim::getJointVelocities(std::vector<double>& result)
00157 {
00158   PCTRL_CHECK_INITIALIZED();
00159   // lock mutex
00160   //
00161   // std::cout << "getConfig: Waiting for Current_Angles_Mutex ... ";
00162   pthread_mutex_lock(&m_AngularVel_Mutex);
00163   // m_Out << "locked"<<endl;
00164   result.resize(m_DOF);
00165   result = m_CurrentAngularVel;
00166   // unlock mutex
00167   //
00168   // m_Out <<"getConfig: Unlocking Angles_Mutex ... ";
00169   pthread_mutex_unlock(&m_AngularVel_Mutex);
00170   // m_Out <<"unlocked "<<endl;
00171 
00172   return true;
00173 }
00174 void PowerCubeSim::setCurrentAngles(std::vector<double> Angles)
00175 {
00176   // std::cout << "setCurrentAngles: " << Angles[0] << " " << Angles[1] << " " << Angles[2] << " " << Angles[3] << " "
00177   // << Angles[4] << " " << Angles[5] << " \n";
00178   pthread_mutex_lock(&m_Angles_Mutex);
00179   // m_Out << "locked"<<endl;
00180 
00181   m_CurrentAngles = Angles;
00182   // unlock mutex
00183   //
00184   // m_Out <<"setCurrentAngles: Unlocking Angles_Mutex ... ";
00185   pthread_mutex_unlock(&m_Angles_Mutex);
00186   // m_Out <<"unlocked "<<endl;
00187 }
00188 
00189 void PowerCubeSim::setCurrentJointVelocities(std::vector<double> AngularVel)
00190 {
00191   // lock mutex
00192   // m_Out << "setCurrentJointVelocities: Waiting for AngularVel_Mutex ... ";
00193   pthread_mutex_lock(&m_AngularVel_Mutex);
00194   // m_Out << "locked"<<endl;
00195 
00196   m_CurrentAngularVel = AngularVel;
00197   // unlock mutex
00198   //
00199   // m_Out <<"setCurrentJointVelocities: Unlocking AngularVel_Mutex ... ";
00200   pthread_mutex_unlock(&m_AngularVel_Mutex);
00201   // m_Out <<"unlocked "<<endl;
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   // Evtl. Fragen zur Rechnung / zum Verfahren an: Felix.Geibel@gmx.de
00215   std::vector<double> acc(m_DOF);
00216   std::vector<double> vel(m_DOF);
00217 
00218   double TG = 0;
00219 
00220   try
00221   {
00222     // Ermittle Joint, der bei max Geschw. und Beschl. am längsten braucht:
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     // determine the joint index that has the greates value for time
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     // Gesamtzeit:
00263     TG = T1 + T2 + T3;
00264 
00265     // Jetzt Geschwindigkeiten und Beschl. für alle:
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         // a und v berechnen:
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   // Errechnete Gesamtzeit zurückgeben (könnte ja nützlich sein)
00291   return true;
00292 }
00293 
00296 double PowerCubeSim::timeRampMove(double dtheta, double vnow, double v, double a)
00297 {
00298   // die Zeiten T1, T2 und T3 errechnen
00299   // ACHTUNG: Hier wird vorläufig angenommen, dass die Bewegung groß ist, d.h. es eine Phase der Bewegung
00300   // mit konst. Geschw. gibt. Der andere Fall wird erst später hinzugefügt.
00301   // m_Out << "DEBUG: timeRampMove" << endl;
00302   // m_Out << "-------------------" << endl;
00303   // m_Out << "dtheta: " << dtheta << ", vnow: " << vnow << ", v: " << v << ", a: " << a << endl;
00304   // m_Out << endl;
00305 
00306   // Wird Joint mit +vmax oder -vmax drehen?
00307   double vm = (dtheta < 0) ? -v : v;
00308   double am = (dtheta < 0) ? -a : a;
00309   // m_Out << "vm: " << vm << endl;
00310   // m_Out << "am: " << am << endl;
00311 
00312   // Zeit bis vm erreicht:
00313   double T1 = (vm - vnow) / am;
00314   // Winkel, der hierbei zurückgelegt wird:
00315   double dtheta1 = vnow * T1 + 0.5 * am * T1 * T1;
00316   // m_Out << "T1: " << T1 << endl;
00317   // m_Out << "dtheta1: " << dtheta1 << endl;
00318 
00319   // Zeit zum Bremsen:
00320   double T3 = vm / am;
00321   // Winkel hierbei:
00322   double dtheta3 = 0.5 * vm * T3;
00323 
00324   // Verbleibender Winkel:
00325   double dtheta2 = dtheta - dtheta1 - dtheta3;
00326   // Also Restzeit (Bew. mit vm):
00327   double T2 = dtheta2 / vm;
00328   // m_Out << "T2: " << T2 << endl;
00329   // m_Out << "dtheta2: " << dtheta2 << endl;
00330   // m_Out << "T3: " << T3 << endl;
00331   // m_Out << "dtheta3: " << dtheta3 << endl;
00332 
00333   // Gesamtzeit zurückgeben:
00334   return T1 + T2 + T3;
00335 }
00336 
00338 bool PowerCubeSim::MoveVel(const std::vector<double>& vel)
00339 {
00340   PCTRL_CHECK_INITIALIZED();
00341   /* TODO
00342         if (getStatus() != PC_CTRL_OK)
00343         {
00344                 printf("PowerCubeSim::MoveVel: canceled!\n");
00345                 return;
00346         }
00347   for(int i=0;i<m_NumOfModules;i++)
00348   {
00349     PCube_moveVel(m_Dev,m_IdModules[i],AngularVelocity[i]);
00350   }
00351   PCube_startMotionAll(m_Dev);
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   // m_Out << "statusMoving: Waiting for Movement_Mutex ... ";
00415   pthread_mutex_lock(&m_Movement_Mutex);
00416   // m_Out << "locked"<<endl;
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   // unlock mutex
00427   // m_Out <<"statusMoving: Unlocking Movement_Mutex ... ";
00428   pthread_mutex_unlock(&m_Movement_Mutex);
00429   // m_Out <<"unlocked "<<endl;
00430 
00431   return isMoving;
00432 }
00433 
00434 bool PowerCubeSim::statusMoving(int cubeNo)
00435 {
00436   PCTRL_CHECK_INITIALIZED();
00437   bool isMoving = false;
00438 
00439   // m_Out << "statusMoving: Waiting for Movement_Mutex ... ";
00440   pthread_mutex_lock(&m_Movement_Mutex);
00441   // m_Out << "locked"<<endl;
00442   if (m_MovementInProgress[cubeNo])
00443   {
00444     isMoving = true;
00445   }
00446 
00447   // unlock mutex
00448   // m_Out <<"statusMoving: Unlocking Movement_Mutex ... ";
00449   pthread_mutex_unlock(&m_Movement_Mutex);
00450   // m_Out <<"unlocked "<<endl;
00451 
00452   return isMoving;
00453 }
00454 
00455 void PowerCubeSim::setStatusMoving(int cubeNo, bool moving)
00456 {
00457   // m_Out << "setStatusMoving: Waiting for Movement_Mutex ... ";
00458   pthread_mutex_lock(&m_Movement_Mutex);
00459   // m_Out << "locked"<<endl;
00460 
00461   m_MovementInProgress[cubeNo] = moving;
00462 
00463   // m_Out <<"setStatusMoving: Unlocking Movement_Mutex ... ";
00464   pthread_mutex_unlock(&m_Movement_Mutex);
00465   // m_Out <<"unlocked "<<endl;
00466 }
00467 
00469 bool PowerCubeSim::statusDec()
00470 {
00471   PCTRL_CHECK_INITIALIZED();
00472   /* TODO
00473   for (int i=0; i<m_NumOfModules; i++)
00474   {
00475     unsigned long status;
00476     PCube_getModuleState(m_Dev,m_IdModules[i], &status);
00477     if (status & STATEID_MOD_RAMP_DEC)
00478       return true;
00479   }
00480   */
00481   return false;
00482 }
00483 
00485 bool PowerCubeSim::statusAcc()
00486 {
00487   PCTRL_CHECK_INITIALIZED();
00488   /* TODO
00489   for (int i=0; i<m_NumOfModules; i++)
00490   {
00491     unsigned long status;
00492     PCube_getModuleState(m_Dev,m_IdModules[i], &status);
00493     if (status & STATEID_MOD_RAMP_ACC)
00494       return true;
00495   }
00496 
00497   */
00498   return false;
00499 }
00500 
00501 void* SimThreadRoutine(void* threadArgs)
00502 {
00503   // get argument
00504   SimThreadArgs* args = (SimThreadArgs*)threadArgs;
00505   PowerCubeSim* cubeSimPtr = args->cubeSimPtr;
00506   int cubeNo = args->cubeID;
00507   double targetAngle = args->targetAngle;
00508 
00509   // std::cout << "Thread started for cube no "<< cubeNo<<"["<<(cubeSimPtr->getModuleMap())[cubeNo]<<"]"<<endl;
00510 
00511   // calculate phases of movement
00512   float t1, t2, t, tges;  // acceleration time t1/t , duration of maximum vel t2, total time tges
00513   double deltaT = SIM_CLOCK_FREQUENCY / 1000;  // clock period
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   // acceleration phase
00525   t1 = maxVel / maxAccel;
00526 
00527   // constant velocity phase
00528   t2 = abs(deltaAngle) / maxVel - t1;
00529 
00530   // cubeSimPtr->getOutputStream()<<" (abs(deltaAngle) >, maxVel*maxVel/maxAccel)?"<< abs(deltaAngle) <<"; "<<
00531   // maxVel*maxVel/maxAccel<<endl;
00532 
00533   // is maxVel reached?
00534   if (abs(deltaAngle) > maxVel * maxVel / maxAccel)
00535   {
00536     tges = 2 * t1 + t2;
00537   }
00538   else
00539   {
00540     // how long will we accelerate?
00541     t = sqrt(abs(deltaAngle) / (maxAccel));
00542     // what velocity will be reached?
00543     // maxVel = maxAccel*t;
00544     tges = 2 * t;
00545   }
00546 
00547   // determine direction of movement
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   // control loop
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) /*||(abs(currDeltaAngle) > 0.001)*/)
00565     // while (abs(deltaAngle)>0.005)
00566     {
00567       // advavnce in simulated time
00568       cubeSimPtr->millisleep((int)SIM_CLOCK_FREQUENCY);
00569       simulatedTime += SIM_CLOCK_FREQUENCY / 1000;  //=n*deltaT
00570       n++;
00571       cubeSimPtr->getJointVelocities(currVels);
00572       // calculate delta phi
00573       double deltaPhi = 0.0;
00574 
00575       // is max Vel reached?
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           // deltaPhi = maxVel*simulatedTime - 0.5*maxAccel*(deltaT - (t1+t2))*(simulatedTime - (t1+t2));
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       // no
00607       else
00608       {
00609         if (simulatedTime < t)
00610         {
00611           // deltaPhi = 0.5*maxAccel*simulatedTime*simulatedTime;
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           // deltaPhi = maxVel *simulatedTime - 0.5*maxAccel*(simulatedTime -t)*(simulatedTime-t);
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       // std::cout << "cube "<<cubeNo<<"["<<simulatedTime<<"]: deltaPhi: "<<deltaPhi<<";
00635       // deltaAngle:"<<currDeltaAngle<<endl;
00636 
00637       // write new angle and velocity
00638       cubeSimPtr->setCurrentAngles(currAngles);
00639       cubeSimPtr->setCurrentJointVelocities(currVels);
00640     }
00641   }
00642 
00643   // we have finished our move
00644   cubeSimPtr->setStatusMoving(cubeNo, false);
00645   currVels[cubeNo] = 0.0;
00646   cubeSimPtr->setCurrentJointVelocities(currVels);
00647 
00648   // cubeSimPtr->getOutputStream() << "Thread finished for cube ID "<< (cubeSimPtr->getModuleMap())[cubeNo]<<endl;
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     // create thread
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   // Millisekunden in Sekunden und Nanosekunden aufteilen
00676   warten.tv_sec = milliseconds / 1000;
00677   warten.tv_nsec = (milliseconds % 1000) * 1000000;
00678   timespec gewartet;
00679   nanosleep(&warten, &gewartet);
00680 }
00681 
00684 /* Not necessary
00685    void PowerCubeSim::HomingDone()
00686    {
00687    for(int i=0; i<m_NumOfModules; i++)
00688    {
00689    unsigned long int help;
00690    std::cout << "Warte auf Modul " << m_IdModules[i] << endl;
00691    do
00692    {
00693    PCube_getModuleState(m_Dev,m_IdModules[i],&help);
00694 //printf("Status: 0x%lx\n",help);
00695 millisleep(100);
00696 } while ( (help & STATEID_MOD_HOME) == 0 );
00697 }
00698 
00699 }
00700 
00701 */
00702 
00703 /*
00704    vector<int> PowerCubeSim::getModuleMap(int dev)
00705    {
00706    vector<int> mod_map;
00707    for( int i = 1; i < MAX_MODULES; i++ )
00708    {
00709    unsigned long serNo;
00710    int ret = PCube_getModuleSerialNo( dev, i, &serNo );
00711    if( ret == 0 )
00712    {
00713    std::cout << "Found module " << i << " with SerialNo " << serNo << "\n";
00714    mod_map.push_back(i);
00715    }
00716 //              else
00717 //              printf( "Module %d not found(%d)\n", i, ret);
00718 
00719 }
00720 return mod_map;
00721 }
00722 */
00723 
00724 /* TODO: necessary?
00725    void PowerCubeSim::waitForSync()
00726    {
00727    for (int i=0; i < m_DOF; i++)
00728    {
00729    unsigned long confword;
00730    millisleep(4);
00731    PCube_getConfig(m_Dev, m_IdModules[i], &confword );
00732    millisleep(4);
00733    PCube_setConfig(m_Dev, m_IdModules[i], confword | CONFIGID_MOD_SYNC_MOTION);
00734    }
00735    }
00736 
00737 */
00738 
00739 /* TODO: necessary?
00740    void PowerCubeSim::dontWaitForSync()
00741    {
00742    for (int i=0; i < m_DOF; i++)
00743    {
00744    unsigned long confword;
00745    millisleep(4);
00746    PCube_getConfig(m_Dev, m_IdModules[i], &confword );
00747    millisleep(4);
00748    PCube_setConfig(m_Dev, m_IdModules[i], confword & (~CONFIGID_MOD_SYNC_MOTION));
00749    }
00750    }
00751    */
00752 
00753 /*
00754    int PowerCubeSim::getStatus()
00755    {
00756 
00757    PC_CTRL_STATE error = PC_CTRL_OK;
00758 
00759    for(int i=0; i<m_NumOfModules; i++)
00760    {
00761    unsigned long int state;
00762    PCube_getModuleState(m_Dev,m_IdModules[i],&state);
00763 
00764    if (state & STATEID_MOD_POW_VOLT_ERR)
00765    {
00766    printf("Error in Module %d: Motor voltage below minimum value!\n",m_IdModules[i]);
00767    error = PC_CTRL_POW_VOLT_ERR;
00768    }
00769    else if (!(state & STATEID_MOD_HOME))
00770    {
00771    printf("Warning: Module %d is not referenced!\n",m_IdModules[i]);
00772    error = PC_CTRL_NOT_REFERENCED;
00773    }
00774    else if (state & STATEID_MOD_ERROR)
00775    {
00776    printf("Error in  Module %d: 0x%lx\n",m_IdModules[i],state);
00777    error = PC_CTRL_ERR;
00778    }
00779    }
00780         return error;
00781 
00782 }*/


schunk_powercube_chain
Author(s): Florian Weisshardt
autogenerated on Sat Jun 8 2019 20:25:18