YouBotManipulator.cpp
Go to the documentation of this file.
1 
2 /****************************************************************
3  *
4  * Copyright (c) 2011
5  * All rights reserved.
6  *
7  * Hochschule Bonn-Rhein-Sieg
8  * University of Applied Sciences
9  * Computer Science Department
10  *
11  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
12  *
13  * Author:
14  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
15  * Supervised by:
16  * Gerhard K. Kraetzschmar
17  *
18  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
19  *
20  * This sofware is published under a dual-license: GNU Lesser General Public
21  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
22  * code may choose which terms they prefer.
23  *
24  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
25  *
26  * Redistribution and use in source and binary forms, with or without
27  * modification, are permitted provided that the following conditions are met:
28  *
29  * * Redistributions of source code must retain the above copyright
30  * notice, this list of conditions and the following disclaimer.
31  * * Redistributions in binary form must reproduce the above copyright
32  * notice, this list of conditions and the following disclaimer in the
33  * documentation and/or other materials provided with the distribution.
34  * * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
35  * contributors may be used to endorse or promote products derived from
36  * this software without specific prior written permission.
37  *
38  * This program is free software: you can redistribute it and/or modify
39  * it under the terms of the GNU Lesser General Public License LGPL as
40  * published by the Free Software Foundation, either version 2.1 of the
41  * License, or (at your option) any later version or the BSD license.
42  *
43  * This program is distributed in the hope that it will be useful,
44  * but WITHOUT ANY WARRANTY; without even the implied warranty of
45  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
46  * GNU Lesser General Public License LGPL and the BSD license for more details.
47  *
48  * You should have received a copy of the GNU Lesser General Public
49  * License LGPL and BSD license along with this program.
50  *
51  ****************************************************************/
54 namespace youbot {
55 
56 YouBotManipulator::YouBotManipulator(const std::string name, const std::string configFilePath)
57 : ethercatMaster(EthercatMaster::getInstance("youbot-ethercat.cfg", configFilePath)) {
58  // Bouml preserved body begin 00067F71
59 
60  this->controllerType = 841;
61  this->alternativeControllerType = 1610;
62  this->supportedFirmwareVersions.push_back("148");
63  this->supportedFirmwareVersions.push_back("200");
65  this->numberArmJoints = 5;
66 
67  string filename;
68  filename = name;
69  filename.append(".cfg");
70  useGripper = true;
71  isGripperInitialized = false;
72  configfile.reset(new ConfigFile(filename, configFilePath));
73 
76  }else{
78  }
79 
80  this->initializeJoints();
81 
82 
83 
84  // Bouml preserved body end 00067F71
85 }
86 
88  // Bouml preserved body begin 00067FF1
90  for (unsigned int i = 0; i < numberArmJoints; i++) {
92  }
93  }
94  // Bouml preserved body end 00067FF1
95 }
96 
99  // Bouml preserved body begin 000A3371
100 
101  if(this->actualFirmwareVersionAllJoints == "148"){
102  this->commutationFirmware148();
103  }else if(this->actualFirmwareVersionAllJoints == "200" ){
104  this->commutationFirmware200();
105  }else{
106  throw std::runtime_error("Unable to commutate joints - Unsupported firmware version!");
107  }
108  // Bouml preserved body end 000A3371
109 }
110 
112 void YouBotManipulator::calibrateManipulator(const bool forceCalibration) {
113  // Bouml preserved body begin 000A9C71
114 
115  //Calibrate all manipulator joints
116  std::vector<JointRoundsPerMinuteSetpoint> calibrationVel;
118  tempdummy.rpm = 0;
119  calibrationVel.assign(numberArmJoints, tempdummy);
120  std::vector<quantity<si::current> > maxCurrent;
121  quantity<si::current> tempdummy2;
122  maxCurrent.assign(numberArmJoints, tempdummy2);
123  std::vector<bool> doCalibration;
124  doCalibration.assign(numberArmJoints, true);
125  std::string jointName;
126 
127  double dummy = 0;
128  char index = 16; // Parameter 0 to 15 of bank 2 are password protected
129 
130  YouBotSlaveMailboxMsg IsCalibratedReadMessage;
131  IsCalibratedReadMessage.stctOutput.moduleAddress = DRIVE;
132  IsCalibratedReadMessage.stctOutput.commandNumber = GGP;
133  IsCalibratedReadMessage.stctOutput.typeNumber = index;
134  IsCalibratedReadMessage.stctOutput.motorNumber = USER_VARIABLE_BANK;
135  IsCalibratedReadMessage.stctOutput.value = 0;
136  IsCalibratedReadMessage.stctInput.value = 0;
137 
138  YouBotSlaveMailboxMsg IsCalibratedSetMessage;
139  IsCalibratedSetMessage.stctOutput.moduleAddress = DRIVE;
140  IsCalibratedSetMessage.stctOutput.commandNumber = SGP;
141  IsCalibratedSetMessage.stctOutput.typeNumber = index;
142  IsCalibratedSetMessage.stctOutput.motorNumber = USER_VARIABLE_BANK;
143  IsCalibratedSetMessage.stctOutput.value = 1;
144 
145 
146  //get parameters for calibration
147  for (unsigned int i = 0; i < numberArmJoints; i++) {
148 
149  std::stringstream jointNameStream;
150  jointNameStream << "Joint_" << i + 1;
151  jointName = jointNameStream.str();
152  bool calib = true;
153  configfile->readInto(calib, jointName, "DoCalibration");
154  doCalibration[i] = calib;
155 
156  joints[i].getConfigurationParameter(IsCalibratedReadMessage);
157  if (IsCalibratedReadMessage.stctInput.value == 1) {
158  doCalibration[i] = false;
159  }
160 
161  if (forceCalibration) {
162  doCalibration[i] = true;
163  }
164 
165  configfile->readInto(dummy, jointName, "CalibrationMaxCurrent_[ampere]");
166  maxCurrent[i] = dummy * ampere;
167  std::string direction;
168  configfile->readInto(direction, jointName, "CalibrationDirection");
169  GearRatio gearRatio;
170  joints[i].getConfigurationParameter(gearRatio);
171  double gearratio = 1;
172  gearRatio.getParameter(gearratio);
173 
174  if (direction == "POSITIV") {
175  calibrationVel[i].rpm = 1 / gearratio;
176  } else if (direction == "NEGATIV") {
177  calibrationVel[i].rpm = -1 / gearratio;
178  } else {
179  throw std::runtime_error("Wrong calibration direction for " + jointName);
180  }
181  }
182 
183 
184  LOG(info) << "Calibrate Manipulator Joints ";
185 
186  std::vector<bool> finished;
187  finished.assign(numberArmJoints, false);
188  int numberUnfinished = numberArmJoints;
189  JointSensedCurrent sensedCurrent;
190 
191 
192  //move the joints slowly in calibration direction
193  for (unsigned int i = 0; i < numberArmJoints; i++) {
194  if (doCalibration[i] == true) {
195  joints[i].setData(calibrationVel[i]);
199  }
200  } else {
201  if (!finished[i]) {
202  finished[i] = true;
203  numberUnfinished--;
204  }
205  }
206  }
207 
208  //monitor the current to find end stop
209  while (numberUnfinished > 0) {
210  for (unsigned int i = 0; i < numberArmJoints; i++) {
214  }
215  joints[i].getData(sensedCurrent);
216  //turn till a max current is reached
217  if (abs(sensedCurrent.current) > abs(maxCurrent[i])) {
218  //stop movement
219  youbot::JointCurrentSetpoint currentStopMovement;
220  currentStopMovement.current = 0 * ampere;
221  joints[i].setData(currentStopMovement);
225  }
226  if (!finished[i]) {
227  finished[i] = true;
228  numberUnfinished--;
229  }
230  }
231  }
232  SLEEP_MILLISEC(1);
233  }
234 
235  // wait to let the joint stop the motion
236  SLEEP_MILLISEC(100);
237 
238  for (unsigned int i = 0; i < numberArmJoints; i++) {
239  if (doCalibration[i] == true) {
240  //set encoder reference position
241  joints[i].setEncoderToZero();
245  }
246  // set a flag in the user variable to remember that it is calibrated
247  joints[i].setConfigurationParameter(IsCalibratedSetMessage);
248  // LOG(info) << "Calibration finished for joint: " << this->jointName;
249  }
250  }
251 
252  //setting joint Limits
253  JointLimits jLimits;
254  for (unsigned int i = 0; i < numberArmJoints; i++) {
255  long upperlimit = 0, lowerlimit = 0;
256  std::stringstream jointNameStream;
257  bool inverted = false;
258  jointNameStream << "Joint_" << i + 1;
259  jointName = jointNameStream.str();
260  JointEncoderSetpoint minEncoderValue;
261  configfile->readInto(lowerlimit, jointName, "LowerLimit_[encoderTicks]");
262  configfile->readInto(upperlimit, jointName, "UpperLimit_[encoderTicks]");
263  configfile->readInto(inverted, jointName, "InverseMovementDirection");
264 
265  if(inverted){
266  minEncoderValue.encoderTicks = lowerlimit + 1000;
267  }else{
268  minEncoderValue.encoderTicks = upperlimit - 1000;
269  }
270 
271  jLimits.setParameter(lowerlimit, upperlimit, true);
272  joints[i].setConfigurationParameter(jLimits);
273  // joints[i].setData(minEncoderValue);
274  }
275 
276  // Bouml preserved body end 000A9C71
277 }
278 
279 void YouBotManipulator::calibrateGripper(const bool forceCalibration) {
280  // Bouml preserved body begin 000A9CF1
281  // Calibrating Gripper
282  bool doCalibration = true;
283  configfile->readInto(doCalibration, "Gripper", "DoCalibration");
284  if(useGripper && doCalibration){
285  CalibrateGripper calibrate;
286  calibrate.setParameter(forceCalibration);
287  gripper->setConfigurationParameter(calibrate);
288  }
289  // Bouml preserved body end 000A9CF1
290 }
291 
294  return numberArmJoints;
295 }
296 
298  return isGripperInitialized;
299 }
300 
303 YouBotJoint& YouBotManipulator::getArmJoint(const unsigned int armJointNumber) {
304  // Bouml preserved body begin 0004F7F1
305 
306  if (armJointNumber <= 0 || armJointNumber > numberArmJoints) {
307  throw std::out_of_range("Invalid Joint Number");
308  }
309  return joints[armJointNumber - 1];
310  // Bouml preserved body end 0004F7F1
311 }
312 
314  // Bouml preserved body begin 0005F9F1
315  if(!useGripper){
316  throw std::runtime_error("The gripper is disabled!");
317  }
318  return *gripper;
319  // Bouml preserved body end 0005F9F1
320 }
321 
325 void YouBotManipulator::setJointData(const std::vector<JointAngleSetpoint>& JointData) {
326  // Bouml preserved body begin 0008FDF1
327  if (JointData.size() != numberArmJoints)
328  throw std::out_of_range("Wrong number of JointAngleSetpoints");
329 
331  for (unsigned int i = 0; i < numberArmJoints; i++)
332  joints[i].setData(JointData[i]);
334 
335  // Bouml preserved body end 0008FDF1
336 }
337 
341 void YouBotManipulator::getJointData(std::vector<JointSensedAngle>& data) {
342  // Bouml preserved body begin 0008FE71
343  data.resize(numberArmJoints);
345  for (unsigned int i = 0; i < numberArmJoints; i++)
346  joints[i].getData(data[i]);
348  // Bouml preserved body end 0008FE71
349 }
350 
354 void YouBotManipulator::setJointData(const std::vector<JointVelocitySetpoint>& JointData) {
355  // Bouml preserved body begin 0008FEF1
356  if (JointData.size() != numberArmJoints)
357  throw std::out_of_range("Wrong number of JointVelocitySetpoints");
358 
360  for (unsigned int i = 0; i < numberArmJoints; i++)
361  joints[i].setData(JointData[i]);
363  // Bouml preserved body end 0008FEF1
364 }
365 
369 void YouBotManipulator::getJointData(std::vector<JointSensedVelocity>& data) {
370  // Bouml preserved body begin 0008FF71
371  data.resize(numberArmJoints);
373  for (unsigned int i = 0; i < numberArmJoints; i++)
374  joints[i].getData(data[i]);
376  // Bouml preserved body end 0008FF71
377 }
378 
382 void YouBotManipulator::setJointData(const std::vector<JointCurrentSetpoint>& JointData) {
383  // Bouml preserved body begin 000CDE71
384  if (JointData.size() != numberArmJoints)
385  throw std::out_of_range("Wrong number of JointCurrentSetpoint");
386 
388  for (unsigned int i = 0; i < numberArmJoints; i++)
389  joints[i].setData(JointData[i]);
391  // Bouml preserved body end 000CDE71
392 }
393 
397 void YouBotManipulator::getJointData(std::vector<JointSensedCurrent>& data) {
398  // Bouml preserved body begin 00090071
399  data.resize(numberArmJoints);
401  for (unsigned int i = 0; i < numberArmJoints; i++)
402  joints[i].getData(data[i]);
404  // Bouml preserved body end 00090071
405 }
406 
410 void YouBotManipulator::setJointData(const std::vector<JointTorqueSetpoint>& JointData) {
411  // Bouml preserved body begin 000CDEF1
412  if (JointData.size() != numberArmJoints)
413  throw std::out_of_range("Wrong number of JointTorqueSetpoint");
414 
416  for (unsigned int i = 0; i < numberArmJoints; i++)
417  joints[i].setData(JointData[i]);
419  // Bouml preserved body end 000CDEF1
420 }
421 
425 void YouBotManipulator::getJointData(std::vector<JointSensedTorque>& data) {
426  // Bouml preserved body begin 000CDF71
427  data.resize(numberArmJoints);
429  for (unsigned int i = 0; i < numberArmJoints; i++)
430  joints[i].getData(data[i]);
432  // Bouml preserved body end 000CDF71
433 }
434 
437  // Bouml preserved body begin 0010D8F1
438 
439  InitializeJoint doInitialization;
440  bool isInitialized = false;
441  int noInitialization = 0;
442  std::string jointName;
443  unsigned int statusFlags;
444  std::vector<bool> isCommutated;
445  isCommutated.assign(numberArmJoints, false);
446  unsigned int u = 0;
447  JointCurrentSetpoint zerocurrent;
448  zerocurrent.current = 0.0 * ampere;
449 
450 
451  ClearMotorControllerTimeoutFlag clearTimeoutFlag;
452  for (unsigned int i = 1; i <= numberArmJoints; i++) {
453  this->getArmJoint(i).setConfigurationParameter(clearTimeoutFlag);
454  }
455 
456  for (unsigned int i = 1; i <= numberArmJoints; i++) {
457  doInitialization.setParameter(false);
458  this->getArmJoint(i).getConfigurationParameter(doInitialization);
459  doInitialization.getParameter(isInitialized);
460  if (!isInitialized) {
461  noInitialization++;
462  }
463  }
464 
465  if (noInitialization != 0) {
466  LOG(info) << "Manipulator Joint Commutation";
467  doInitialization.setParameter(true);
468 
469  JointRoundsPerMinuteSetpoint rpmSetpoint(100);
470 
472  for (unsigned int i = 1; i <= numberArmJoints; i++)
473  this->getArmJoint(i).setData(rpmSetpoint);
475 
476 
477  // check for the next 5 sec if the joints are commutated
478  for (u = 1; u <= 5000; u++) {
479  for (unsigned int i = 1; i <= numberArmJoints; i++) {
480  this->getArmJoint(i).getStatus(statusFlags);
481  if (statusFlags & INITIALIZED) {
482  isCommutated[i - 1] = true;
483  this->getArmJoint(i).setData(zerocurrent);
484  }
485  }
489  }
490  if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3] && isCommutated[4]) {
491  break;
492  }
493  SLEEP_MILLISEC(1);
494  }
495 
496  for (unsigned int i = 1; i <= numberArmJoints; i++) {
497  this->getArmJoint(i).setData(zerocurrent);
501  }
502  doInitialization.setParameter(false);
503  this->getArmJoint(i).getConfigurationParameter(doInitialization);
504  doInitialization.getParameter(isInitialized);
505  if (!isInitialized) {
506  std::stringstream jointNameStream;
507  jointNameStream << "manipulator joint " << i;
508  jointName = jointNameStream.str();
509  throw std::runtime_error("Could not commutate " + jointName);
510  }
511  }
512  }
513  // Bouml preserved body end 0010D8F1
514 }
515 
518  // Bouml preserved body begin 0010D971
519 
520  InitializeJoint doInitialization;
521  bool isInitialized = false;
522  int noInitialization = 0;
523  std::string jointName;
524 
525 
526  ClearMotorControllerTimeoutFlag clearTimeoutFlag;
527  for (unsigned int i = 1; i <= numberArmJoints; i++) {
528  this->getArmJoint(i).setConfigurationParameter(clearTimeoutFlag);
529  }
530 
531  for (unsigned int i = 1; i <= numberArmJoints; i++) {
532  doInitialization.setParameter(false);
533  this->getArmJoint(i).getConfigurationParameter(doInitialization);
534  doInitialization.getParameter(isInitialized);
535  if (!isInitialized) {
536  noInitialization++;
537  }
538  }
539 
540  if (noInitialization != 0) {
541  LOG(info) << "Manipulator Joint Commutation";
542  doInitialization.setParameter(true);
543 
545  for (unsigned int i = 1; i <= numberArmJoints; i++)
546  this->getArmJoint(i).setConfigurationParameter(doInitialization);
548 
549  unsigned int statusFlags;
550  std::vector<bool> isCommutated;
551  isCommutated.assign(numberArmJoints, false);
552  unsigned int u = 0;
553 
554  // check for the next 5 sec if the joints are commutated
555  for (u = 1; u <= 5000; u++) {
556  for (unsigned int i = 1; i <= numberArmJoints; i++) {
560  }
561  this->getArmJoint(i).getStatus(statusFlags);
562  if (statusFlags & INITIALIZED) {
563  isCommutated[i - 1] = true;
564  }
565  }
566  if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3] && isCommutated[4]) {
567  break;
568  }
569  SLEEP_MILLISEC(1);
570  }
571 
572  SLEEP_MILLISEC(10); // the controller likes it
573 
574  for (unsigned int i = 1; i <= numberArmJoints; i++) {
575  doInitialization.setParameter(false);
576  this->getArmJoint(i).getConfigurationParameter(doInitialization);
577  doInitialization.getParameter(isInitialized);
578  if (!isInitialized) {
579  std::stringstream jointNameStream;
580  jointNameStream << "manipulator joint " << i;
581  jointName = jointNameStream.str();
582  throw std::runtime_error("Could not commutate " + jointName);
583  }
584  }
585  }
586 
587 
588  // Bouml preserved body end 0010D971
589 }
590 
592  // Bouml preserved body begin 00068071
593 
594  // LOG(info) << "Initializing Joints";
595 
596  //enable overriding the number of joints
597  if (configfile->keyExists("JointTopology", "NumberJoints"))
598  configfile->readInto(numberArmJoints, "JointTopology", "NumberJoints");
599 
600  //get number of slaves
601  unsigned int noSlaves = ethercatMaster.getNumberOfSlaves();
602 
603  if (noSlaves < numberArmJoints) {
604  throw std::runtime_error("Not enough ethercat slaves were found to create a YouBotManipulator!");
605  }
606 
607  unsigned int slaveNumber = 0;
608  for (unsigned int i = 1; i <= numberArmJoints; i++) {
609  std::stringstream jointConfigNameStream;
610  jointConfigNameStream << "ManipulatorJoint" << i;
611  std::string jointConfigName = jointConfigNameStream.str();
612 
613  configfile->readInto(slaveNumber, "JointTopology", jointConfigName);
614  if (slaveNumber <= noSlaves) {
615  joints.push_back(new YouBotJoint(slaveNumber));
616  } else {
617  throw std::out_of_range("The ethercat slave number is not available!");
618  }
619  }
620 
621  //Configure Joint Parameters
622  std::string jointName;
623  JointName jName;
624  GearRatio gearRatio;
625  EncoderTicksPerRound ticksPerRound;
626  InverseMovementDirection inverseDir;
627  double gearRatio_numerator = 0;
628  double gearRatio_denominator = 1;
629  FirmwareVersion firmwareTypeVersion;
630  TorqueConstant torqueConst;
631  double trajectory_p=0, trajectory_i=0, trajectory_d=0, trajectory_imax=0, trajectory_imin=0;
632 
633 
634  for (unsigned int i = 0; i < numberArmJoints; i++) {
635  std::stringstream jointNameStream;
636  jointNameStream << "Joint_" << i + 1;
637  jointName = jointNameStream.str();
638 
639 
640  joints[i].getConfigurationParameter(firmwareTypeVersion);
641  std::string version;
642  int controllerType;
643  std::string firmwareVersion;
644  firmwareTypeVersion.getParameter(controllerType, firmwareVersion);
645 
646  string name;
647  configfile->readInto(name, jointName, "JointName");
648  jName.setParameter(name);
649 
650  LOG(info) << name << "\t Controller Type: " << controllerType << " Firmware version: " << firmwareVersion;
651 
652  if (this->controllerType != controllerType && alternativeControllerType != controllerType) {
653  std::stringstream ss;
654  ss << "The youBot manipulator motor controller have to be of type: " << this->controllerType << " or " << alternativeControllerType;
655  throw std::runtime_error(ss.str().c_str());
656  }
657 
658  //check if firmware is supported
659  bool isfirmwareSupported = false;
660  for(unsigned int d = 0; d < supportedFirmwareVersions.size(); d++){
661  if(this->supportedFirmwareVersions[d] == firmwareVersion){
662  isfirmwareSupported = true;
663  break;
664  }
665  }
666 
667  if(!isfirmwareSupported){
668  throw std::runtime_error("Unsupported firmware version: " + firmwareVersion);
669  }
670 
671  if(this->actualFirmwareVersionAllJoints == ""){
672  this->actualFirmwareVersionAllJoints = firmwareVersion;
673  }
674 
675  if(!(firmwareVersion == this->actualFirmwareVersionAllJoints)){
676  throw std::runtime_error("All joints must have the same firmware version!");
677  }
678 
679  configfile->readInto(gearRatio_numerator, jointName, "GearRatio_numerator");
680  configfile->readInto(gearRatio_denominator, jointName, "GearRatio_denominator");
681  gearRatio.setParameter(gearRatio_numerator / gearRatio_denominator);
682  int ticks;
683  configfile->readInto(ticks, jointName, "EncoderTicksPerRound");
684  ticksPerRound.setParameter(ticks);
685 
686  double torqueConstant;
687  configfile->readInto(torqueConstant, jointName, "TorqueConstant_[newton_meter_divided_by_ampere]");
688  torqueConst.setParameter(torqueConstant);
689 
690  bool invdir = false;
691  configfile->readInto(invdir, jointName, "InverseMovementDirection");
692  inverseDir.setParameter(invdir);
693 
694  joints[i].setConfigurationParameter(jName);
695  joints[i].setConfigurationParameter(gearRatio);
696  joints[i].setConfigurationParameter(ticksPerRound);
697  joints[i].setConfigurationParameter(torqueConst);
698  joints[i].setConfigurationParameter(inverseDir);
699 
700  //Joint Trajectory Controller
702  configfile->readInto(trajectory_p, jointName, "trajectory_controller_P");
703  configfile->readInto(trajectory_i, jointName, "trajectory_controller_I");
704  configfile->readInto(trajectory_d, jointName, "trajectory_controller_D");
705  configfile->readInto(trajectory_imax, jointName, "trajectory_controller_I_max");
706  configfile->readInto(trajectory_imin, jointName, "trajectory_controller_I_min");
707  joints[i].trajectoryController.setConfigurationParameter(trajectory_p, trajectory_i, trajectory_d, trajectory_imax, trajectory_imin);
708  joints[i].trajectoryController.setEncoderTicksPerRound(ticks);
709  joints[i].trajectoryController.setGearRatio(gearRatio_numerator / gearRatio_denominator);
710  joints[i].trajectoryController.setInverseMovementDirection(invdir);
711  ethercatMasterWithThread->registerJointTrajectoryController(&(joints[i].trajectoryController), joints[i].getJointNumber());
712  }
713  }
714 
715 
716  configfile->readInto(useGripper, "Gripper", "EnableGripper");
717 
718  if (useGripper) {
719  try {
720  //Initializing Gripper
721  configfile->readInto(slaveNumber, "JointTopology", "ManipulatorJoint5");
722  this->gripper.reset(new YouBotGripper(slaveNumber));
723  BarSpacingOffset barOffest;
724  MaxTravelDistance maxDistance;
725  MaxEncoderValue maxEncoder;
726  GripperBarName BarName;
727  double dummy = 0;
728  int controllerType;
729  double firmwareVersion;
730  string barname;
731 
732  GripperFirmwareVersion gripperVersion;
733  this->gripper->getConfigurationParameter(gripperVersion);
734  gripperVersion.getParameter(controllerType, firmwareVersion);
735 
736  LOG(info) << "Gripper" << "\t\t Controller Type: " << controllerType << " Firmware version: " << firmwareVersion;
737 
738  // Gripper Bar 1
739  configfile->readInto(barname, "GripperBar1", "BarName");
740  BarName.setParameter(barname);
741  this->gripper->getGripperBar1().setConfigurationParameter(BarName);
742 
743  configfile->readInto(dummy, "GripperBar1", "BarSpacingOffset_[meter]");
744  barOffest.setParameter(dummy * meter);
745  this->gripper->getGripperBar1().setConfigurationParameter(barOffest);
746 
747  configfile->readInto(dummy, "GripperBar1", "MaxTravelDistance_[meter]");
748  maxDistance.setParameter(dummy * meter);
749  this->gripper->getGripperBar1().setConfigurationParameter(maxDistance);
750 
751  int maxenc = 0;
752  configfile->readInto(maxenc, "GripperBar1", "MaxEncoderValue");
753  maxEncoder.setParameter(maxenc);
754  this->gripper->getGripperBar1().setConfigurationParameter(maxEncoder);
755 
756  int stallThreshold = 0;
757  configfile->readInto(stallThreshold, "GripperBar1", "StallGuard2Threshold");
758  StallGuard2Threshold threshold;
759  threshold.setParameter(stallThreshold);
760  this->gripper->getGripperBar1().setConfigurationParameter(threshold);
761 
762  bool stallGuardFilter = false;
763  configfile->readInto(stallGuardFilter, "GripperBar1", "StallGuard2FilterEnable");
765  filter.setParameter(stallGuardFilter);
766  this->gripper->getGripperBar1().setConfigurationParameter(filter);
767 
768  // Gripper Bar 2
769  configfile->readInto(barname, "GripperBar2", "BarName");
770  BarName.setParameter(barname);
771  this->gripper->getGripperBar2().setConfigurationParameter(BarName);
772 
773  configfile->readInto(dummy, "GripperBar2", "BarSpacingOffset_[meter]");
774  barOffest.setParameter(dummy * meter);
775  this->gripper->getGripperBar2().setConfigurationParameter(barOffest);
776 
777  configfile->readInto(dummy, "GripperBar2", "MaxTravelDistance_[meter]");
778  maxDistance.setParameter(dummy * meter);
779  this->gripper->getGripperBar2().setConfigurationParameter(maxDistance);
780 
781  configfile->readInto(maxenc, "GripperBar2", "MaxEncoderValue");
782  maxEncoder.setParameter(maxenc);
783  this->gripper->getGripperBar2().setConfigurationParameter(maxEncoder);
784 
785  configfile->readInto(stallThreshold, "GripperBar2", "StallGuard2Threshold");
786  threshold.setParameter(stallThreshold);
787  this->gripper->getGripperBar2().setConfigurationParameter(threshold);
788 
789  configfile->readInto(stallGuardFilter, "GripperBar2", "StallGuard2FilterEnable");
790  filter.setParameter(stallGuardFilter);
791  this->gripper->getGripperBar2().setConfigurationParameter(filter);
792  } catch (std::exception &e) {
793  isGripperInitialized = false;
794  return;
795  }
796 
797  isGripperInitialized = true;
798  }
799 
800  return;
801  // Bouml preserved body end 00068071
802 }
803 
804 
805 } // namespace youbot
void setParameter(const quantity< si::length > &parameter)
d
void doJointCommutation()
does the sine commutation of the arm joints
void setParameter(const unsigned int parameter)
void setParameter(const quantity< si::length > &parameter)
void setParameter(const int parameter)
YouBotManipulator(const std::string name, const std::string configFilePath="../config/")
the firmware version of the joint
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
The Ethercat Master factory.
virtual void getConfigurationParameter(JointParameter &parameter)
Definition: YouBotJoint.cpp:83
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
The encoder value when the gripper has reached it&#39;s maximum bar spacing position. ...
EthercatMasterWithThread * ethercatMasterWithThread
void setParameter(const double parameter)
void setParameter(const bool parameter)
ROSCPP_DECL bool isInitialized()
void setParameter(const std::string parameter)
virtual void setData(const JointDataSetpoint &data)
joint position limits in encoder ticks
virtual void setConfigurationParameter(const JointParameter &parameter)
Definition: YouBotJoint.cpp:77
Reads and writes a configuration file.
Definition: ConfigFile.hpp:125
void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
The youBot gripper with one degree of freedom.
the name of the joint
void registerJointTrajectoryController(JointTrajectoryController *object, const unsigned int JointNumber)
void calibrateManipulator(const bool forceCalibration=false)
calibrate the reference position of the arm joints
void setParameter(const std::string parameter)
The maximum bar spacing distance of the gripper.
Clear the flag that indicates a communication timeout between the EtherCAT master and the controller...
void getParameter(double &parameter) const
virtual bool sendProcessData()=0
boost::ptr_vector< YouBotJoint > joints
#define LOG(level)
Definition: Logger.hpp:102
virtual void AutomaticReceiveOn(const bool enableAutomaticReceive)=0
boost::scoped_ptr< ConfigFile > configfile
The number of manipulator joints.
virtual bool receiveProcessData()=0
the gear ratio which is needed for the calculations in the youBot driver
virtual void setJointData(const std::vector< JointAngleSetpoint > &JointData)
Sensed electric current of the joint.
Definition: JointData.hpp:136
encoder ticks setpoint of the joint
Definition: JointData.hpp:242
int getNumberJoints()
return the number of joints
std::vector< std::string > supportedFirmwareVersions
EtherCAT mailbox message of the youBot slaves.
YouBotJoint & getArmJoint(const unsigned int armJointNumber)
void setParameter(const double parameter)
inverse the joint movement direction
virtual void getJointData(std::vector< JointSensedAngle > &data)
Represents a bar spacing offset. It could be useful if the gripper can not be totally closed...
#define SLEEP_MILLISEC(millisec)
Definition: Time.hpp:60
the firmware version of the gripper
boost::scoped_ptr< YouBotGripper > gripper
void commutationFirmware200()
does the commutation of the arm joints with firmware 2.0
void setParameter(const int lowerLimit, const int upperLimit, const bool activateLimits)
void setParameter(const bool parameter)
virtual void AutomaticSendOn(const bool enableAutomaticSend)=0
virtual void getStatus(std::vector< std::string > &statusMessages)
Returns the status messages for the motor controller.
void getParameter(int &controllerType, std::string &firmwareVersion) const
void setParameter(const bool parameter)
Set-point current of the joint.
Definition: JointData.hpp:206
The name for a gripper bar or finger.
void setParameter(const bool parameter)
quantity< si::current > current
Definition: JointData.hpp:208
#define USER_VARIABLE_BANK
void calibrateGripper(const bool forceCalibration=false)
void getParameter(int &controllerType, double &firmwareVersion) const
static EthercatMasterInterface & getInstance(const std::string configFile="youbot-ethercat.cfg", const std::string configFilePath="../config/", const bool ethercatMasterWithThread=true)
void commutationFirmware148()
does the commutation of the arm joints with firmware 1.48 and below
EthercatMasterInterface & ethercatMaster
void setParameter(const unsigned int parameter)
quantity< si::current > current
Definition: JointData.hpp:138
virtual unsigned int getNumberOfSlaves() const =0
return the quantity of ethercat slave which have an input/output buffer
abstract data class for joints
Definition: JointData.hpp:61
void getParameter(bool &parameter) const
Rounds per minute set-point of the joint.
Definition: JointData.hpp:194


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:26