24 #define PCTRL_CHECK_INITIALIZED() \
25 if (isInitialized() == false) \
27 m_ErrorMessage.assign("Manipulator not initialized."); \
31 #define Ready4MoveStep 4638
38 m_mutex = PTHREAD_MUTEX_INITIALIZER;
90 std::cout <<
" D O F :" << DOF << std::endl;
98 std::cout <<
"=========================================================================== " << std::endl;
99 std::cout <<
"PowerCubeCtrl:Init: Trying to initialize with the following parameters: " << std::endl;
100 std::cout <<
"DOF: " << DOF << std::endl;
101 std::cout <<
"CanModule: " << CanModule << std::endl;
102 std::cout <<
"CanDevice: " << CanDevice << std::endl;
103 std::cout <<
"CanBaudrate: " << CanBaudrate << std::endl;
104 std::cout <<
"ModulIDs: ";
105 for (
int i = 0; i < DOF; i++)
107 std::cout << ModulIDs[i] <<
" ";
109 std::cout << std::endl;
111 std::cout << std::endl <<
"maxVel: ";
112 for (
int i = 0; i < DOF; i++)
114 std::cout << MaxVel[i] <<
" ";
117 std::cout << std::endl <<
"maxAcc: ";
118 for (
int i = 0; i < DOF; i++)
120 std::cout << MaxAcc[i] <<
" ";
123 std::cout << std::endl <<
"upperLimits: ";
124 for (
int i = 0; i < DOF; i++)
126 std::cout << UpperLimits[i] <<
" ";
129 std::cout << std::endl <<
"lowerLimits: ";
130 for (
int i = 0; i < DOF; i++)
132 std::cout << LowerLimits[i] <<
" ";
135 std::cout << std::endl <<
"offsets: ";
136 for (
int i = 0; i < DOF; i++)
138 std::cout << Offsets[i] <<
" ";
141 std::cout << std::endl <<
"=========================================================================== " << std::endl;
142 std::ostringstream InitStr;
143 InitStr << CanModule <<
":" << CanDevice <<
"," << CanBaudrate;
144 std::cout <<
"initstring = " << InitStr.str().c_str() << std::endl;
149 pthread_mutex_unlock(&
m_mutex);
152 std::ostringstream errorMsg;
153 errorMsg <<
"Could not open device " << CanDevice <<
", m5api error code: " << ret;
162 for (
int i = 0; i < DOF; i++)
164 for (
int reset_try = 0; reset_try < max_tries; reset_try++)
168 pthread_mutex_unlock(&
m_mutex);
174 else if ((ret != 0) && (reset_try == (max_tries - 1)))
176 std::ostringstream errorMsg;
177 errorMsg <<
"Could not reset module " << ModulIDs.at(i) <<
" during init. Errorcode during reset: " << ret <<
" Try to init once more.";
188 std::cout <<
"number of moduleIDs" << ModulIDs.size() << std::endl;
193 pthread_mutex_unlock(&
m_mutex);
194 std::cout <<
"found " << number_of_modules <<
" modules." << std::endl;
197 for (
int i = 0; i < DOF; i++)
200 unsigned short verNo;
201 unsigned long defConfig;
202 std::vector<std::string> Module_Types;
207 pthread_mutex_unlock(&
m_mutex);
210 std::ostringstream errorMsg;
211 errorMsg <<
"Could not find Module with ID " << ModulIDs[i] <<
", m5api error code: " << ret;
219 pthread_mutex_unlock(&
m_mutex);
222 std::ostringstream errorMsg;
223 errorMsg <<
"Could not find Module with ID " << ModulIDs[i] <<
", m5api error code: " << ret;
236 pthread_mutex_unlock(&
m_mutex);
239 std::ostringstream errorMsg;
240 errorMsg <<
"Could not get Module type with ID " << ModulIDs[i] <<
", m5api error code: " << ret;
248 std::cout <<
"gear ratio: " << gear_ratio << std::endl;
257 pthread_mutex_unlock(&
m_mutex);
260 std::ostringstream errorMsg;
261 errorMsg <<
"Could not get Module type with ID " << ModulIDs[i] <<
", m5api error code: " << ret;
269 std::cout <<
"wrong module type configured. Type must be rotary axis. Use Windows configuration software to change type." << std::endl;
278 pthread_mutex_unlock(&
m_mutex);
280 ROS_DEBUG(
"module type check: %li (std::dec)", defConfig);
284 std::ostringstream errorMsg;
285 errorMsg <<
"Error on communication with module " << ModulIDs[i] <<
", m5api error code: " << ret;
298 ROS_DEBUG(
"Module %i is from type: PRL", i);
303 ROS_DEBUG(
"Module %i is from type: PW", i);
307 std::cout <<
"Found module " << std::dec << ModulIDs[i] <<
" Serial: " << serNo <<
" Version: " << std::hex << verNo << std::endl;
315 std::vector<std::string> errorMessages;
325 bool successful =
false;
329 std::cout <<
"PowerCubeCtrl:Init: homing not successful, aborting ...\n";
350 pthread_mutex_unlock(&
m_mutex);
376 std::cout <<
"Starting MoveJointSpaceSync(Jointd Angle) ... " << std::endl;
379 std::vector<double> acc(DOF);
380 std::vector<double> vel(DOF);
381 std::vector<double> posnow(DOF);
382 std::vector<double> velnow(DOF);
398 std::vector<double> times(DOF);
399 for (
int i = 0; i < DOF; i++)
401 RampCommand rm(posnow[i], velnow[i], target_pos[i], m_maxAcc[i], m_maxVel[i]);
407 double max = times[0];
408 for (
int i = 1; i < DOF; i++)
417 RampCommand rm_furthest(posnow[furthest], velnow[furthest], target_pos[furthest], m_maxAcc[furthest], m_maxVel[furthest]);
419 double T1 = rm_furthest.
T1();
420 double T2 = rm_furthest.
T2();
421 double T3 = rm_furthest.
T3();
425 acc[furthest] = m_maxAcc[furthest];
426 vel[furthest] = m_maxVel[furthest];
428 for (
int i = 0; i < DOF; i++)
458 std::ostringstream errorMsg;
463 for (
int i = 0; i < DOF; i++)
465 if (fabs(posnow[i] - target_pos[i]) > 1e-3)
467 double v = fabs(vel[i]);
468 double a = fabs(acc[i]);
472 errorMsg <<
"Module " << ModulIDs[i] <<
" PCube_moveRamp returned " << ret << std::endl;
482 errorMsg <<
"PCube_startMotionAll returned " << ret << std::endl;
506 std::vector<double> velocities;
507 velocities.resize(DOF);
510 std::ostringstream errorMsg;
512 std::vector<std::string> errorMessages;
515 std::vector<float> delta_pos;
516 std::vector<float> delta_pos_horizon;
517 delta_pos.resize(DOF);
518 delta_pos_horizon.resize(DOF);
520 std::vector<float> target_pos;
521 std::vector<float> target_pos_horizon;
523 target_pos.resize(DOF);
524 target_pos_horizon.resize(DOF);
526 float target_time_horizon = 0;
548 std::vector<double> pos_temp;
549 pos_temp.resize(DOF);
551 for (
unsigned int i = 0; i < DOF; i++)
555 if (delta_t >= 0.050)
561 target_time = delta_t;
565 target_time_horizon = target_time + (float)
m_horizon;
567 delta_pos_horizon[i] = target_time_horizon * velocities[i];
568 delta_pos[i] = target_time * velocities[i];
570 ROS_DEBUG(
"delta_pos[%i]: %f target_time: %f velocitiy[%i]: %f", i, delta_pos[i], target_time, i, velocities[i]);
573 target_pos_horizon[i] =
m_positions[i] + delta_pos_horizon[i] - Offsets[i];
580 if (velocities.size() != DOF)
582 m_ErrorMessage =
"Skipping command: Commanded velocities and DOF are not same dimension.";
586 for (
unsigned int i = 0; i < DOF; i++)
589 if (velocities[i] > maxVels[i])
592 velocities[i] = maxVels[i];
596 ROS_INFO(
"Velocity %f exceeds limit %f for axis %i. moving with max velocity %f instead", velocities[i], maxVels[i], i, maxVels[i]);
603 if ((target_pos[i] < LowerLimits[i] + Offsets[i]) && (velocities[i] < 0))
605 ROS_INFO(
"Skipping command: %f Target position exceeds lower limit (%f).", target_pos[i], LowerLimits[i]);
610 pthread_mutex_unlock(&
m_mutex);
616 if ((target_pos[i] > UpperLimits[i] + Offsets[i]) && (velocities[i] > 0))
618 ROS_INFO(
"Skipping command: %f Target position exceeds upper limit (%f).", target_pos[i], UpperLimits[i]);
623 pthread_mutex_unlock(&
m_mutex);
636 for (
unsigned int i = 0; i < DOF; i++)
640 ROS_INFO(
"Error during movement. Status: %i \n", status);
647 unsigned short time4motion = (
unsigned short)((target_time_horizon)*1000.0);
649 for (
unsigned int i = 0; i < DOF; i++)
660 pthread_mutex_unlock(&
m_mutex);
666 pthread_mutex_unlock(&
m_mutex);
680 m_positions[i] = (double)pos + delta_pos[i] + Offsets[i];
682 pos_temp[i] = (double)pos;
692 pthread_mutex_unlock(&
m_mutex);
704 std::vector<double>
null;
705 for (
unsigned int i = 0; i < DOF; i++)
721 for (
unsigned int i = 0; i < DOF; i++)
740 for (
unsigned int i = 0; i < DOF; i++)
744 pthread_mutex_unlock(&
m_mutex);
747 std::ostringstream errorMsg;
748 errorMsg <<
"Could not reset all modules, m5api error code: " << ret;
758 for (
unsigned int i = 0; i < DOF; i++)
762 pthread_mutex_unlock(&
m_mutex);
765 std::ostringstream errorMsg;
766 errorMsg <<
"Could not reset all modules, m5api error code: " << ret;
785 std::vector<std::string> errorMessages;
794 for (
unsigned int i = 0; i < DOF; i++)
798 pthread_mutex_unlock(&
m_mutex);
802 std::cout <<
"State: Error com with Module: " << i <<
" Time: " <<
ros::Time::now() << std::endl;
811 pthread_mutex_unlock(&
m_mutex);
815 std::cout <<
"State: Error com with Module: " << i <<
" Time: " <<
ros::Time::now() << std::endl;
873 pthread_mutex_unlock(&
m_mutex);
876 std::ostringstream errorMsg;
877 errorMsg <<
"Could not set MaxVelocity in Module ID: " << ModulIDs[i] <<
", m5api error code: " << ret;
882 std::vector<double> maxVelocities(maxVelocity);
903 pthread_mutex_unlock(&
m_mutex);
906 std::ostringstream errorMsg;
907 errorMsg <<
"Could not set MaxVelocity in Module ID: " << ModulIDs[i] <<
", m5api error code: " << ret;
934 pthread_mutex_unlock(&
m_mutex);
937 std::ostringstream errorMsg;
938 errorMsg <<
"Could not set MaxAcceleration in Module ID: " << ModulIDs[i] <<
", m5api error code: " << ret;
943 std::vector<double> maxAccelerations(maxAcceleration);
963 pthread_mutex_unlock(&
m_mutex);
966 std::ostringstream errorMsg;
967 errorMsg <<
"Could not set MaxAcceleration in Module ID: " << ModulIDs[i] <<
", m5api error code: " << ret;
1015 unsigned long confword;
1020 pthread_mutex_unlock(&
m_mutex);
1025 pthread_mutex_unlock(&
m_mutex);
1028 std::ostringstream errorMsg;
1029 errorMsg <<
"Could not set SyncMotion in Module ID: " << ModulIDs[i] <<
", m5api error code: " << ret;
1052 unsigned long confword;
1057 pthread_mutex_unlock(&
m_mutex);
1062 pthread_mutex_unlock(&
m_mutex);
1080 unsigned long state;
1082 std::vector<std::string> ErrorMessages;
1084 std::ostringstream errorMsg;
1090 for (
unsigned int i = 0; i < DOF; i++)
1095 pthread_mutex_unlock(&
m_mutex);
1100 ROS_DEBUG(
"Error on com in UpdateStates");
1125 for (
unsigned int i = 0; i < ErrorMessages.size(); i++)
1143 std::vector<PC_CTRL_STATUS> StatusArray;
1144 StatusArray.resize(DOF);
1146 errorMessages.clear();
1147 errorMessages.resize(DOF);
1151 for (
unsigned int i = 0; i < DOF; i++)
1153 std::ostringstream errorMsg;
1159 errorMsg <<
"Error in Module " << ModuleIDs[i] <<
": ";
1160 errorMsg <<
"Motor voltage below minimum value! Check Emergency Stop!";
1161 errorMessages[i] = errorMsg.str();
1165 errorMsg <<
"Error in Module " << ModuleIDs[i] <<
": ";
1166 errorMsg <<
"Overheated power transitors! Power must be switched of to reset this error.";
1167 errorMessages[i] = errorMsg.str();
1171 errorMsg <<
"Error in Module " << ModuleIDs[i] <<
": ";
1172 errorMsg <<
"The drive has been overloaded and the servo loop has been disabled. Power must be switched off to reset this error.";
1173 errorMessages[i] = errorMsg.str();
1179 errorMsg <<
"Error in Module " << ModuleIDs[i] <<
": ";
1180 errorMsg <<
"The servo loop was not able to follow the target position!";
1181 errorMessages[i] = errorMsg.str();
1189 pthread_mutex_unlock(&
m_mutex);
1191 errorMsg <<
"Error in Module " << ModuleIDs[i];
1192 errorMsg <<
" : Status code: " << std::hex <<
m_status[i];
1193 errorMessages[i] = errorMsg.str();
1199 errorMsg <<
"PowerCubeCtrl is in global error state";
1200 errorMessages[i] = errorMsg.str();
1205 errorMsg <<
"Module with Id " << ModuleIDs[i];
1206 errorMsg <<
": Status OK.";
1207 errorMessages[i] = errorMsg.str();
1213 for (
unsigned int i = 0; i < DOF; i++)
1215 if ((
int)StatusArray[i] <= (
int)status)
1217 status = StatusArray[i];
1290 pthread_mutex_unlock(&
m_mutex);
1293 std::cout <<
"PCubeCtrl::getConfig(): getPos(" << ModulIDs[i] <<
") return " << ret << std::endl;
1318 pthread_mutex_unlock(&
m_mutex);
1321 std::cout <<
"PCubeCtrl::getConfig(): getVel(" << ModulIDs[i] <<
") return " << ret << std::endl;
1346 double max_homing_time = 15.0;
1347 double homing_time = 999.0;
1348 double intervall = 0.1;
1356 for (
unsigned int i = 0; i < DOF; i++)
1360 pthread_mutex_unlock(&
m_mutex);
1363 if ((position > UpperLimits[i] + Offsets[i]) || (position < LowerLimits[i] + Offsets[i]))
1365 std::ostringstream errorMsg;
1366 errorMsg <<
"Module " << ModuleIDs[i] <<
" has position " << position <<
" that is outside limits (" << UpperLimits[i] + Offsets[i] <<
" <-> " << LowerLimits[i] + Offsets[i] << std::endl;
1369 std::cout <<
"Position error for PW-Module. Init is aborted. Try to reboot the robot." << std::endl;
1376 ROS_INFO(
"Position of Module %i is outside limits. Module can only be moved in opposite direction.", i);
1381 ROS_INFO(
"Module type incorrect. (in func. PowerCubeCtrl::doHoming();)");
1395 pthread_mutex_unlock(&
m_mutex);
1412 pthread_mutex_unlock(&
m_mutex);
1418 ROS_INFO(
"Error while sending homing command to Module: %i. I try to reset the module.", i);
1423 pthread_mutex_unlock(&
m_mutex);
1426 std::ostringstream errorMsg;
1427 errorMsg <<
"Can't reset module after homing error" << ModuleIDs[i] <<
", m5api error code: " << ret;
1436 pthread_mutex_unlock(&
m_mutex);
1439 std::ostringstream errorMsg;
1440 errorMsg <<
"Can't start homing for module " << ModuleIDs[i] <<
", tried reset with no success, m5api error code: " << ret;
1457 for (
unsigned int i = 0; i < DOF; i++)
1459 unsigned long int help;
1464 pthread_mutex_unlock(&
m_mutex);
1465 ROS_DEBUG(
"Homing active for Module: %i State: %li", ModuleIDs.at(i),
help);
1468 usleep(intervall * 1000000);
1469 homing_time += intervall;
1470 if (homing_time >= max_homing_time)
1479 ROS_DEBUG(
"State of Module %i : %li", ModuleIDs.at(i),
help);
1482 for (
unsigned int i = 0; i < DOF; i++)
1487 std::cout <<
"Homing failed: Error in Module " << ModuleIDs[i] << std::endl;
1492 ROS_INFO(
"Homing for Modul %i done.", ModuleIDs.at(i));
1513 unsigned long puiValue;
1515 *dio = (
unsigned char)puiValue;