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/simulatedArm.h>
00055 #include <cob_powercube_chain/simulatedMotor.h>
00056 #include <math.h>
00057
00058 #define PSIM_CHECK_INITIALIZED() \
00059 if ( isInitialized()==false ) \
00060 { \
00061 m_ErrorMessage.assign("Manipulator not initialized."); \
00062 return false; \
00063 }
00064
00065 simulatedArm::simulatedArm()
00066 {
00067 std::cerr << "==============Starting Simulated Powercubes\n";
00068 m_DOF = 0;
00069 m_Initialized = false;
00070 m_motors.clear();
00071
00072 }
00073
00074 simulatedArm::~simulatedArm()
00075 {
00076
00077 ;
00078 }
00079
00080 bool simulatedArm::Init(PowerCubeCtrlParams * params)
00081 {
00082 m_DOF = params->GetNumberOfDOF();;
00083
00084 double vmax = 1.0;
00085 double amax = 1.5;
00086
00087 setMaxVelocity(vmax);
00088 setMaxAcceleration(amax);
00089 m_maxVel.resize(m_DOF);
00090 m_maxAcc.resize(m_DOF);
00091
00092 std::vector<double> ul(m_DOF);
00093 std::vector<double> ll(m_DOF);
00094 ul = params->GetUpperLimits();
00095 ll = params->GetLowerLimits();
00096 m_maxVel = params->GetMaxVel();
00097 m_maxAcc = params->GetMaxAcc();
00098
00099
00100 for (int i=0; i < m_DOF; i++)
00101 {
00102 m_motors.push_back( simulatedMotor(ll[i], ul[i], amax, vmax) );
00103 }
00104 std::cerr << "===========Initializing Simulated Powercubes\n";
00105 m_Initialized = true;
00106 return true;
00107 }
00108
00110 bool simulatedArm::Stop()
00111 {
00112 for (int i=0; i < m_DOF; i++)
00113 m_motors[i].stop();
00114 return true;
00115 }
00116
00117 bool simulatedArm::MoveJointSpaceSync(const std::vector<double>& target)
00118 {
00119 std::cerr << "======================TUTUTUTUT\n";
00120 PSIM_CHECK_INITIALIZED();
00121
00122
00123 std::vector<double> acc(m_DOF);
00124 std::vector<double> vel(m_DOF);
00125
00126 double TG = 0;
00127
00128
00129 try
00130 {
00131
00132
00133 std::vector<double> posnow;
00134 posnow.resize(m_DOF);
00135 if ( getConfig(posnow) == false )
00136 return false;
00137
00138 std::vector<double> velnow;
00139 velnow.resize(m_DOF);
00140 if ( getJointVelocities(velnow) == false )
00141 return false;
00142
00143 std::vector<double> times(m_DOF);
00144
00145 for (int i=0; i < m_DOF; i++)
00146 {
00147 RampCommand rm(posnow[i], velnow[i], target[i], m_maxAcc[i], m_maxVel[i]);
00148 times[i] = rm.getTotalTime();
00149 }
00150
00151
00152 int furthest = 0;
00153
00154 double max = times[0];
00155
00156 for (int i=1; i<m_DOF; i++)
00157 {
00158 if (times[i] > max)
00159 {
00160 max = times[i];
00161 furthest = i;
00162 }
00163 }
00164
00165 RampCommand rm_furthest(posnow[furthest], velnow[furthest], target[furthest], m_maxAcc[furthest], m_maxVel[furthest]);
00166
00167 double T1 = rm_furthest.T1();
00168 double T2 = rm_furthest.T2();
00169 double T3 = rm_furthest.T3();
00170
00171
00172 TG = T1 + T2 + T3;
00173
00174
00175 acc[furthest] = m_maxAcc[furthest];
00176 vel[furthest] = m_maxVel[furthest];
00177
00178 for (int i = 0; i < m_DOF; i++)
00179 {
00180 if (i != furthest)
00181 {
00182 double a; double v;
00183
00184 RampCommand::calculateAV(
00185 posnow[i],
00186 velnow[i],
00187 target[i],
00188 TG, T3,
00189 m_maxAcc[i],
00190 m_maxVel[i],
00191 a,
00192 v);
00193
00194 acc[i] = a;
00195 vel[i] = v;
00196 }
00197 }
00198 }
00199 catch(...)
00200 {
00201 m_ErrorMessage.assign("Problem during calculation of a and av.");
00202 return false;
00203 }
00204
00205
00206 for (int i=0; i < m_DOF; i++)
00207 {
00208 std::cout << "moving motor " << i << ": " << target[i] << ": " << vel[i] << ": " << acc[i] << "\n";
00209 m_motors[i].moveRamp(target[i], vel[i], acc[i]);
00210 }
00211
00212 return true;
00213 }
00214
00215 bool simulatedArm::MoveVel(const std::vector<double>& Vel)
00216 {
00217 PSIM_CHECK_INITIALIZED();
00218
00219
00220
00221 for (int i=0; i < m_DOF; i++)
00222 {
00223
00224 m_motors[i].moveVel(Vel[i]);
00225 }
00226
00227 return true;
00228 }
00229
00230
00231 bool simulatedArm::MovePos(const std::vector<double>& Pos)
00232 {
00233 PSIM_CHECK_INITIALIZED();
00234
00235 for (int i=0; i < m_DOF; i++)
00236 m_motors[i].movePos(Pos[i]);
00237
00238 return true;
00239 }
00240
00241
00243
00245
00247 bool simulatedArm::setMaxVelocity(double radpersec)
00248 {
00249 PSIM_CHECK_INITIALIZED();
00250
00251 m_maxVel.resize(m_DOF);
00252
00253 for (int i=0; i < m_DOF; i++)
00254 {
00255 m_maxAcc[i] = radpersec;
00256 m_motors[i].setMaxVelocity(radpersec);
00257 }
00258
00259 return true;
00260 }
00261
00262 bool simulatedArm::setMaxVelocity(const std::vector<double>& radpersec)
00263 {
00264 PSIM_CHECK_INITIALIZED();
00265
00266 m_maxAcc = radpersec;
00267
00268 for (int i=0; i < m_DOF; i++)
00269 m_motors[i].setMaxVelocity(radpersec[i]);
00270
00271 return true;
00272 }
00273
00275 bool simulatedArm::setMaxAcceleration(double radPerSecSquared)
00276 {
00277 PSIM_CHECK_INITIALIZED();
00278
00279 for (int i=0; i < m_DOF; i++)
00280 m_motors[i].setMaxAcceleration(radPerSecSquared);
00281
00282 return true;
00283 }
00284
00285 bool simulatedArm::setMaxAcceleration(const std::vector<double>& radPerSecSquared)
00286 {
00287 PSIM_CHECK_INITIALIZED();
00288
00289 for (int i=0; i < m_DOF; i++)
00290 m_motors[i].setMaxAcceleration(radPerSecSquared[i]);
00291
00292 return true;
00293 }
00294
00295
00297
00299
00300
00302 bool simulatedArm::getConfig(std::vector<double>& result)
00303 {
00304 PSIM_CHECK_INITIALIZED();
00305
00306 result.resize(m_DOF);
00307 for (int i=0; i < m_DOF; i++)
00308 {
00309 result[i] = m_motors[i].getAngle();
00310 }
00311
00312 return true;
00313 }
00314
00316 bool simulatedArm::getJointVelocities(std::vector<double>& result)
00317 {
00318 PSIM_CHECK_INITIALIZED();
00319
00320 result.resize(m_DOF);
00321 for (int i=0; i < m_DOF; i++)
00322 {
00323 result[i] = m_motors[i].getVelocity();
00324 }
00325
00326 return true;
00327 }
00328
00331 bool simulatedArm::statusMoving()
00332 {
00333 PSIM_CHECK_INITIALIZED();
00334
00335 for(int i=0; i<m_DOF; i++)
00336 {
00337 if (m_motors[i].statusMoving())
00338 return true;
00339 }
00340 return false;
00341 }
00342
00343
00345 bool simulatedArm::statusDec()
00346 {
00347 PSIM_CHECK_INITIALIZED();
00348
00349 for(int i=0; i<m_DOF; i++)
00350 {
00351 if (m_motors[i].statusDec())
00352 return true;
00353 }
00354 return false;
00355 }
00356
00358 bool simulatedArm::statusAcc()
00359 {
00360 PSIM_CHECK_INITIALIZED();
00361
00362 for(int i=0; i<m_DOF; i++)
00363 {
00364 if (m_motors[i].statusAcc())
00365 return true;
00366 }
00367 return false;
00368 }
00369