YouBotBase.cpp
Go to the documentation of this file.
1 /****************************************************************
2  *
3  * Copyright (c) 2011
4  * All rights reserved.
5  *
6  * Hochschule Bonn-Rhein-Sieg
7  * University of Applied Sciences
8  * Computer Science Department
9  *
10  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
11  *
12  * Author:
13  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
14  * Supervised by:
15  * Gerhard K. Kraetzschmar
16  *
17  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
18  *
19  * This sofware is published under a dual-license: GNU Lesser General Public
20  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
21  * code may choose which terms they prefer.
22  *
23  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
24  *
25  * Redistribution and use in source and binary forms, with or without
26  * modification, are permitted provided that the following conditions are met:
27  *
28  * * Redistributions of source code must retain the above copyright
29  * notice, this list of conditions and the following disclaimer.
30  * * Redistributions in binary form must reproduce the above copyright
31  * notice, this list of conditions and the following disclaimer in the
32  * documentation and/or other materials provided with the distribution.
33  * * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
34  * contributors may be used to endorse or promote products derived from
35  * this software without specific prior written permission.
36  *
37  * This program is free software: you can redistribute it and/or modify
38  * it under the terms of the GNU Lesser General Public License LGPL as
39  * published by the Free Software Foundation, either version 2.1 of the
40  * License, or (at your option) any later version or the BSD license.
41  *
42  * This program is distributed in the hope that it will be useful,
43  * but WITHOUT ANY WARRANTY; without even the implied warranty of
44  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
45  * GNU Lesser General Public License LGPL and the BSD license for more details.
46  *
47  * You should have received a copy of the GNU Lesser General Public
48  * License LGPL and BSD license along with this program.
49  *
50  ****************************************************************/
53 namespace youbot {
54 
55 YouBotBase::YouBotBase(const std::string name, const std::string configFilePath)
56 : ethercatMaster(EthercatMaster::getInstance("youbot-ethercat.cfg", configFilePath)) {
57  // Bouml preserved body begin 00067E71
58 
59  this->controllerType = 174;
60  this->alternativeControllerType = 1632;
61  this->supportedFirmwareVersions.push_back("148");
62  this->supportedFirmwareVersions.push_back("200");
64 
65  string filename;
66  filename = name;
67  filename.append(".cfg");
68 
69  configfile.reset(new ConfigFile(filename, configFilePath));
70 
73  }else{
75  }
76 
77  this->initializeJoints();
78 
79  this->initializeKinematic();
80 
81  // Bouml preserved body end 00067E71
82 }
83 
85  // Bouml preserved body begin 00067EF1
87  for (unsigned int i = 0; i < BASEJOINTS; i++) {
89  }
90  }
91  // Bouml preserved body end 00067EF1
92 }
93 
96  // Bouml preserved body begin 0008A9F1
97 
98  if(this->actualFirmwareVersionAllJoints == "148"){
99  this->commutationFirmware148();
100  }else if(this->actualFirmwareVersionAllJoints == "200" ){
101  this->commutationFirmware200();
102  }else{
103  throw std::runtime_error("Unable to commutate joints - Unsupported firmware version!");
104  }
105  // Bouml preserved body end 0008A9F1
106 }
107 
110 YouBotJoint& YouBotBase::getBaseJoint(const unsigned int baseJointNumber) {
111  // Bouml preserved body begin 0004F771
112  if (baseJointNumber <= 0 || baseJointNumber > BASEJOINTS) {
113  throw std::out_of_range("Invalid Joint Number");
114  }
115  return joints[baseJointNumber - 1];
116  // Bouml preserved body end 0004F771
117 }
118 
123 void YouBotBase::getBasePosition(quantity<si::length>& longitudinalPosition, quantity<si::length>& transversalPosition, quantity<plane_angle>& orientation) {
124  // Bouml preserved body begin 000514F1
125 
126  std::vector<quantity<plane_angle> > wheelPositions;
127  quantity<plane_angle> dummy;
128  JointSensedAngle sensedPos;
129  wheelPositions.assign(BASEJOINTS, dummy);
130 
132  joints[0].getData(sensedPos);
133  wheelPositions[0] = sensedPos.angle;
134  joints[1].getData(sensedPos);
135  wheelPositions[1] = sensedPos.angle;
136  joints[2].getData(sensedPos);
137  wheelPositions[2] = sensedPos.angle;
138  joints[3].getData(sensedPos);
139  wheelPositions[3] = sensedPos.angle;
141 
142  youBotBaseKinematic.wheelPositionsToCartesianPosition(wheelPositions, longitudinalPosition, transversalPosition, orientation);
143  // Bouml preserved body end 000514F1
144 }
145 
150 void YouBotBase::setBasePosition(const quantity<si::length>& longitudinalPosition, const quantity<si::length>& transversalPosition, const quantity<plane_angle>& orientation) {
151  // Bouml preserved body begin 000C0971
152 
153  std::vector<quantity<plane_angle> > wheelPositions;
154  quantity<plane_angle> dummy;
155  JointAngleSetpoint setpointPos;
156  wheelPositions.assign(BASEJOINTS, dummy);
157  JointSensedAngle sensedPos;
158 
159  youBotBaseKinematic.cartesianPositionToWheelPositions(longitudinalPosition, transversalPosition, orientation, wheelPositions);
160 
161  if (wheelPositions.size() < BASEJOINTS)
162  throw std::out_of_range("To less wheel velocities");
163 
164  joints[0].setEncoderToZero();
165  joints[1].setEncoderToZero();
166  joints[2].setEncoderToZero();
167  joints[3].setEncoderToZero();
168  SLEEP_MILLISEC(10);
169 
171  joints[0].getData(sensedPos);
172  setpointPos.angle = sensedPos.angle + wheelPositions[0];
173  joints[0].setData(setpointPos);
174 
175  joints[1].getData(sensedPos);
176  setpointPos.angle = sensedPos.angle + wheelPositions[1];
177  joints[1].setData(setpointPos);
178 
179  joints[2].getData(sensedPos);
180  setpointPos.angle = sensedPos.angle + wheelPositions[2];
181  joints[2].setData(setpointPos);
182 
183  joints[3].getData(sensedPos);
184  setpointPos.angle = sensedPos.angle + wheelPositions[3];
185  joints[3].setData(setpointPos);
187 
188  // Bouml preserved body end 000C0971
189 }
190 
195 void YouBotBase::getBaseVelocity(quantity<si::velocity>& longitudinalVelocity, quantity<si::velocity>& transversalVelocity, quantity<si::angular_velocity>& angularVelocity) {
196  // Bouml preserved body begin 00051271
197 
198  std::vector<quantity<angular_velocity> > wheelVelocities;
199  quantity<angular_velocity> dummy;
200  JointSensedVelocity sensedVel;
201  wheelVelocities.assign(BASEJOINTS, dummy);
202 
204  joints[0].getData(sensedVel);
205  wheelVelocities[0] = sensedVel.angularVelocity;
206  joints[1].getData(sensedVel);
207  wheelVelocities[1] = sensedVel.angularVelocity;
208  joints[2].getData(sensedVel);
209  wheelVelocities[2] = sensedVel.angularVelocity;
210  joints[3].getData(sensedVel);
211  wheelVelocities[3] = sensedVel.angularVelocity;
213 
214  youBotBaseKinematic.wheelVelocitiesToCartesianVelocity(wheelVelocities, longitudinalVelocity, transversalVelocity, angularVelocity);
215 
216  // Bouml preserved body end 00051271
217 }
218 
223 void YouBotBase::setBaseVelocity(const quantity<si::velocity>& longitudinalVelocity, const quantity<si::velocity>& transversalVelocity, const quantity<si::angular_velocity>& angularVelocity) {
224  // Bouml preserved body begin 0004DD71
225 
226  std::vector<quantity<angular_velocity> > wheelVelocities;
227  JointVelocitySetpoint setVel;
228 
229  youBotBaseKinematic.cartesianVelocityToWheelVelocities(longitudinalVelocity, transversalVelocity, angularVelocity, wheelVelocities);
230 
231  if (wheelVelocities.size() < BASEJOINTS)
232  throw std::out_of_range("To less wheel velocities");
233 
235  setVel.angularVelocity = wheelVelocities[0];
236  joints[0].setData(setVel);
237  setVel.angularVelocity = wheelVelocities[1];
238  joints[1].setData(setVel);
239  setVel.angularVelocity = wheelVelocities[2];
240  joints[2].setData(setVel);
241  setVel.angularVelocity = wheelVelocities[3];
242  joints[3].setData(setVel);
244  // Bouml preserved body end 0004DD71
245 }
246 
250 void YouBotBase::setJointData(const std::vector<JointAngleSetpoint>& JointData) {
251  // Bouml preserved body begin 0008F9F1
252  if (JointData.size() != BASEJOINTS)
253  throw std::out_of_range("Wrong number of JointAngleSetpoints");
254 
256  joints[0].setData(JointData[0]);
257  joints[1].setData(JointData[1]);
258  joints[2].setData(JointData[2]);
259  joints[3].setData(JointData[3]);
261 
262  // Bouml preserved body end 0008F9F1
263 }
264 
268 void YouBotBase::getJointData(std::vector<JointSensedAngle>& data) {
269  // Bouml preserved body begin 0008FBF1
270  data.resize(BASEJOINTS);
272  joints[0].getData(data[0]);
273  joints[1].getData(data[1]);
274  joints[2].getData(data[2]);
275  joints[3].getData(data[3]);
277  // Bouml preserved body end 0008FBF1
278 }
279 
283 void YouBotBase::setJointData(const std::vector<JointVelocitySetpoint>& JointData) {
284  // Bouml preserved body begin 0008FA71
285  if (JointData.size() != BASEJOINTS)
286  throw std::out_of_range("Wrong number of JointVelocitySetpoints");
287 
289  joints[0].setData(JointData[0]);
290  joints[1].setData(JointData[1]);
291  joints[2].setData(JointData[2]);
292  joints[3].setData(JointData[3]);
294  // Bouml preserved body end 0008FA71
295 }
296 
300 void YouBotBase::getJointData(std::vector<JointSensedVelocity>& data) {
301  // Bouml preserved body begin 0008FC71
302  data.resize(BASEJOINTS);
304  joints[0].getData(data[0]);
305  joints[1].getData(data[1]);
306  joints[2].getData(data[2]);
307  joints[3].getData(data[3]);
309  // Bouml preserved body end 0008FC71
310 }
311 
315 void YouBotBase::setJointData(const std::vector<JointCurrentSetpoint>& JointData) {
316  // Bouml preserved body begin 000CDFF1
317  if (JointData.size() != BASEJOINTS)
318  throw std::out_of_range("Wrong number of JointCurrentSetpoint");
319 
321  joints[0].setData(JointData[0]);
322  joints[1].setData(JointData[1]);
323  joints[2].setData(JointData[2]);
324  joints[3].setData(JointData[3]);
326  // Bouml preserved body end 000CDFF1
327 }
328 
332 void YouBotBase::getJointData(std::vector<JointSensedCurrent>& data) {
333  // Bouml preserved body begin 0008FD71
334  data.resize(BASEJOINTS);
336  joints[0].getData(data[0]);
337  joints[1].getData(data[1]);
338  joints[2].getData(data[2]);
339  joints[3].getData(data[3]);
341  // Bouml preserved body end 0008FD71
342 }
343 
347 void YouBotBase::setJointData(const std::vector<JointTorqueSetpoint>& JointData) {
348  // Bouml preserved body begin 000CE071
349  if (JointData.size() != BASEJOINTS)
350  throw std::out_of_range("Wrong number of JointTorqueSetpoint");
351 
353  joints[0].setData(JointData[0]);
354  joints[1].setData(JointData[1]);
355  joints[2].setData(JointData[2]);
356  joints[3].setData(JointData[3]);
358  // Bouml preserved body end 000CE071
359 }
360 
364 void YouBotBase::getJointData(std::vector<JointSensedTorque>& data) {
365  // Bouml preserved body begin 000CE0F1
366  data.resize(BASEJOINTS);
368  joints[0].getData(data[0]);
369  joints[1].getData(data[1]);
370  joints[2].getData(data[2]);
371  joints[3].getData(data[3]);
373  // Bouml preserved body end 000CE0F1
374 }
375 
378  // Bouml preserved body begin 0010D9F1
379 
380  InitializeJoint doInitialization;
381  bool isInitialized = false;
382  int noInitialization = 0;
383  std::string jointName;
384  unsigned int statusFlags;
385  std::vector<bool> isCommutated;
386  isCommutated.assign(BASEJOINTS, false);
387  unsigned int u = 0;
388  JointCurrentSetpoint zerocurrent;
389  zerocurrent.current = 0.0 * ampere;
390 
391 
392  ClearMotorControllerTimeoutFlag clearTimeoutFlag;
393  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
394  this->getBaseJoint(i).setConfigurationParameter(clearTimeoutFlag);
395  }
396 
397  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
398  doInitialization.setParameter(false);
399  this->getBaseJoint(i).getConfigurationParameter(doInitialization);
400  doInitialization.getParameter(isInitialized);
401  if (!isInitialized) {
402  noInitialization++;
403  }
404  }
405 
406  if (noInitialization != 0) {
407  LOG(info) << "Base Joint Commutation with firmware 2.0";
408  doInitialization.setParameter(true);
409 
410  JointRoundsPerMinuteSetpoint rpmSetpoint(100);
411 
413  this->getBaseJoint(1).setData(rpmSetpoint);
414  this->getBaseJoint(2).setData(rpmSetpoint);
415  this->getBaseJoint(3).setData(rpmSetpoint);
416  this->getBaseJoint(4).setData(rpmSetpoint);
418  rpmSetpoint.rpm = 0;
419 
420 
421  // check for the next 5 sec if the joints are commutated
422  for (u = 1; u <= 5000; u++) {
423  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
424  this->getBaseJoint(i).getStatus(statusFlags);
425  if (statusFlags & INITIALIZED) {
426  isCommutated[i - 1] = true;
427  this->getBaseJoint(i).setData(rpmSetpoint);
428  }
429  }
433  }
434  if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3]) {
435  break;
436  }
437  SLEEP_MILLISEC(1);
438  }
439 
440  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
441  this->getBaseJoint(i).setData(rpmSetpoint);
445  }
446  doInitialization.setParameter(false);
447  this->getBaseJoint(i).getConfigurationParameter(doInitialization);
448  doInitialization.getParameter(isInitialized);
449  if (!isInitialized) {
450  std::stringstream jointNameStream;
451  jointNameStream << "base joint " << i;
452  jointName = jointNameStream.str();
453  throw std::runtime_error("Could not commutate " + jointName);
454  }
455  }
456  }
457  // Bouml preserved body end 0010D9F1
458 }
459 
462  // Bouml preserved body begin 0010DA71
463 
464  InitializeJoint doInitialization;
465  bool isInitialized = false;
466  int noInitialization = 0;
467  std::string jointName;
468 
469 
470  ClearMotorControllerTimeoutFlag clearTimeoutFlag;
471  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
472  this->getBaseJoint(i).setConfigurationParameter(clearTimeoutFlag);
473  }
474 
475  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
476  doInitialization.setParameter(false);
477  this->getBaseJoint(i).getConfigurationParameter(doInitialization);
478  doInitialization.getParameter(isInitialized);
479  if (!isInitialized) {
480  noInitialization++;
481  }
482  }
483 
484  if (noInitialization != 0) {
485  LOG(info) << "Base Joint Commutation with firmware 1.48";
486  doInitialization.setParameter(true);
487 
489  this->getBaseJoint(1).setConfigurationParameter(doInitialization);
490  this->getBaseJoint(2).setConfigurationParameter(doInitialization);
491  this->getBaseJoint(3).setConfigurationParameter(doInitialization);
492  this->getBaseJoint(4).setConfigurationParameter(doInitialization);
494 
495  unsigned int statusFlags;
496  std::vector<bool> isCommutated;
497  isCommutated.assign(BASEJOINTS, false);
498  unsigned int u = 0;
499 
500  // check for the next 5 sec if the joints are commutated
501  for (u = 1; u <= 5000; u++) {
502  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
506  }
507  this->getBaseJoint(i).getStatus(statusFlags);
508  if (statusFlags & INITIALIZED) {
509  isCommutated[i - 1] = true;
510  }
511  }
512  if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3]) {
513  break;
514  }
515  SLEEP_MILLISEC(1);
516  }
517 
518  SLEEP_MILLISEC(10); // the controller likes it
519 
520  for (unsigned int i = 1; i <= BASEJOINTS; i++) {
521  doInitialization.setParameter(false);
522  this->getBaseJoint(i).getConfigurationParameter(doInitialization);
523  doInitialization.getParameter(isInitialized);
524  if (!isInitialized) {
525  std::stringstream jointNameStream;
526  jointNameStream << "base joint " << i;
527  jointName = jointNameStream.str();
528  throw std::runtime_error("Could not commutate " + jointName);
529  }
530  }
531  }
532 
533 
534  // Bouml preserved body end 0010DA71
535 }
536 
538  // Bouml preserved body begin 000464F1
539 
540  LOG(trace) << "Initializing Joints";
541 
542  //get number of slaves
543  unsigned int noSlaves = ethercatMaster.getNumberOfSlaves();
544 
545  if (noSlaves < BASEJOINTS) {
546  throw std::out_of_range("Not enough ethercat slaves were found to create a YouBotBase!");
547  }
548 
549  //read Joint Topology from config file
550  // configfile.setSection("JointTopology");
551 
552  //check if enough slave exist to create YouBotJoint for the slave numbers from config file
553  //if enough slave exist create YouBotJoint and store it in the joints vector
554  unsigned int slaveNumber = 0;
555  configfile->readInto(slaveNumber, "JointTopology", "BaseLeftFront");
556  if (slaveNumber <= noSlaves) {
557  joints.push_back(new YouBotJoint(slaveNumber));
558  } else {
559  throw std::out_of_range("The ethercat slave number is not available!");
560  }
561 
562  configfile->readInto(slaveNumber, "JointTopology", "BaseRightFront");
563  if (slaveNumber <= noSlaves) {
564  joints.push_back(new YouBotJoint(slaveNumber));
565  } else {
566  throw std::out_of_range("The ethercat slave number is not available!");
567  }
568 
569  configfile->readInto(slaveNumber, "JointTopology", "BaseLeftBack");
570  if (slaveNumber <= noSlaves) {
571  joints.push_back(new YouBotJoint(slaveNumber));
572  } else {
573  throw std::out_of_range("The ethercat slave number is not available!");
574  }
575 
576  configfile->readInto(slaveNumber, "JointTopology", "BaseRightBack");
577  if (slaveNumber <= noSlaves) {
578  joints.push_back(new YouBotJoint(slaveNumber));
579  } else {
580  throw std::out_of_range("The ethercat slave number is not available!");
581  }
582 
583 
584  //Configure Joint Parameters
585  std::string jointName;
586  JointName jName;
587  GearRatio gearRatio;
588  EncoderTicksPerRound ticksPerRound;
589  InverseMovementDirection inverseDir;
590  FirmwareVersion firmwareTypeVersion;
591  TorqueConstant torqueConst;
592 
593  double trajectory_p=0, trajectory_i=0, trajectory_d=0, trajectory_imax=0, trajectory_imin=0;
594  double gearRatio_numerator = 0;
595  double gearRatio_denominator = 1;
596  JointLimits jLimits;
597 
598  for (unsigned int i = 0; i < BASEJOINTS; i++) {
599  std::stringstream jointNameStream;
600  jointNameStream << "Joint_" << i + 1;
601  jointName = jointNameStream.str();
602  // configfile.setSection(jointName.c_str());
603 
604  joints[i].getConfigurationParameter(firmwareTypeVersion);
605  std::string version;
606  int controllerType;
607  std::string firmwareVersion;
608  firmwareTypeVersion.getParameter(controllerType, firmwareVersion);
609 
610  string name;
611  configfile->readInto(name, jointName, "JointName");
612  jName.setParameter(name);
613 
614  LOG(info) << name << "\t Controller Type: " << controllerType << " Firmware version: " << firmwareVersion;
615 
616  if (this->controllerType != controllerType && alternativeControllerType != controllerType) {
617  std::stringstream ss;
618  ss << "The youBot base motor controller have to be of type: " << this->controllerType << " or " << alternativeControllerType;
619  throw std::runtime_error(ss.str().c_str());
620  }
621 
622  //check if firmware is supported
623  bool isfirmwareSupported = false;
624  for(unsigned int d = 0; d < supportedFirmwareVersions.size(); d++){
625  if(this->supportedFirmwareVersions[d] == firmwareVersion){
626  isfirmwareSupported = true;
627  break;
628  }
629  }
630 
631  if(!isfirmwareSupported){
632  throw std::runtime_error("Unsupported firmware version: "+ firmwareVersion);
633  }
634 
635  if(this->actualFirmwareVersionAllJoints == ""){
636  this->actualFirmwareVersionAllJoints = firmwareVersion;
637  }
638 
639  if(!(firmwareVersion == this->actualFirmwareVersionAllJoints)){
640  throw std::runtime_error("All joints must have the same firmware version!");
641  }
642 
643  configfile->readInto(gearRatio_numerator, jointName, "GearRatio_numerator");
644  configfile->readInto(gearRatio_denominator, jointName, "GearRatio_denominator");
645  gearRatio.setParameter(gearRatio_numerator / gearRatio_denominator);
646  int ticks;
647  configfile->readInto(ticks, jointName, "EncoderTicksPerRound");
648  ticksPerRound.setParameter(ticks);
649 
650  double torqueConstant;
651  configfile->readInto(torqueConstant, jointName, "TorqueConstant_[newton_meter_divided_by_ampere]");
652  torqueConst.setParameter(torqueConstant);
653 
654  bool invdir = false;
655  configfile->readInto(invdir, jointName, "InverseMovementDirection");
656  inverseDir.setParameter(invdir);
657 
658  joints[i].setConfigurationParameter(jName);
659  joints[i].setConfigurationParameter(gearRatio);
660  joints[i].setConfigurationParameter(ticksPerRound);
661  joints[i].setConfigurationParameter(torqueConst);
662  joints[i].setConfigurationParameter(inverseDir);
663 
664  long upperlimit = 0, lowerlimit = 0;
665  configfile->readInto(lowerlimit, jointName, "LowerLimit_[encoderTicks]");
666  configfile->readInto(upperlimit, jointName, "UpperLimit_[encoderTicks]");
667 
668  jLimits.setParameter(lowerlimit, upperlimit, false);
669  joints[i].setConfigurationParameter(jLimits);
670 
671  //Joint Trajectory Controller
673  configfile->readInto(trajectory_p, jointName, "trajectory_controller_P");
674  configfile->readInto(trajectory_i, jointName, "trajectory_controller_I");
675  configfile->readInto(trajectory_d, jointName, "trajectory_controller_D");
676  configfile->readInto(trajectory_imax, jointName, "trajectory_controller_I_max");
677  configfile->readInto(trajectory_imin, jointName, "trajectory_controller_I_min");
678  joints[i].trajectoryController.setConfigurationParameter(trajectory_p, trajectory_i, trajectory_d, trajectory_imax, trajectory_imin);
679  joints[i].trajectoryController.setEncoderTicksPerRound(ticks);
680  joints[i].trajectoryController.setGearRatio(gearRatio_numerator / gearRatio_denominator);
681  joints[i].trajectoryController.setInverseMovementDirection(invdir);
682  ethercatMasterWithThread->registerJointTrajectoryController(&(joints[i].trajectoryController), joints[i].getJointNumber());
683  }
684  }
685 
686  return;
687  // Bouml preserved body end 000464F1
688 }
689 
691  // Bouml preserved body begin 0004DDF1
693 
694  //read the kinematics parameter from a config file
695  configfile->readInto(kinematicConfig.rotationRatio, "YouBotKinematic", "RotationRatio");
696  configfile->readInto(kinematicConfig.slideRatio, "YouBotKinematic", "SlideRatio");
697  double dummy = 0;
698  configfile->readInto(dummy, "YouBotKinematic", "LengthBetweenFrontAndRearWheels_[meter]");
699  kinematicConfig.lengthBetweenFrontAndRearWheels = dummy * meter;
700  configfile->readInto(dummy, "YouBotKinematic", "LengthBetweenFrontWheels_[meter]");
701  kinematicConfig.lengthBetweenFrontWheels = dummy * meter;
702  configfile->readInto(dummy, "YouBotKinematic", "WheelRadius_[meter]");
703  kinematicConfig.wheelRadius = dummy * meter;
704 
705 
706  youBotBaseKinematic.setConfiguration(kinematicConfig);
707  // Bouml preserved body end 0004DDF1
708 }
709 
710 
711 } // namespace youbot
YouBotBase(const std::string name, const std::string configFilePath="../config/")
Definition: YouBotBase.cpp:55
d
void setParameter(const unsigned int parameter)
std::string actualFirmwareVersionAllJoints
Definition: YouBotBase.hpp:186
the firmware version of the joint
std::vector< std::string > supportedFirmwareVersions
Definition: YouBotBase.hpp:184
virtual void wheelVelocitiesToCartesianVelocity(const std::vector< quantity< angular_velocity > > &wheelVelocities, quantity< si::velocity > &longitudinalVelocity, quantity< si::velocity > &transversalVelocity, quantity< angular_velocity > &angularVelocity)
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 ...
quantity< angular_velocity > angularVelocity
Definition: JointData.hpp:184
void setParameter(const double parameter)
void commutationFirmware200()
does the commutation of the arm joints with firmware 2.0
Definition: YouBotBase.cpp:377
void setParameter(const bool parameter)
ROSCPP_DECL bool isInitialized()
Set-point velocity of the joint.
Definition: JointData.hpp:182
void setParameter(const std::string parameter)
virtual void setData(const JointDataSetpoint &data)
joint position limits in encoder ticks
virtual void getJointData(std::vector< JointSensedAngle > &data)
Definition: YouBotBase.cpp:268
virtual void setConfigurationParameter(const JointParameter &parameter)
Definition: YouBotJoint.cpp:77
Reads and writes a configuration file.
Definition: ConfigFile.hpp:125
void setConfiguration(const FourSwedishWheelOmniBaseKinematicConfiguration &configuration)
void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
the name of the joint
void registerJointTrajectoryController(JointTrajectoryController *object, const unsigned int JointNumber)
void getBaseVelocity(quantity< si::velocity > &longitudinalVelocity, quantity< si::velocity > &transversalVelocity, quantity< si::angular_velocity > &angularVelocity)
Definition: YouBotBase.cpp:195
void commutationFirmware148()
does the commutation of the arm joints with firmware 1.48 and below
Definition: YouBotBase.cpp:461
EthercatMasterWithThread * ethercatMasterWithThread
Definition: YouBotBase.hpp:182
#define BASEJOINTS
The number of base joints.
Definition: YouBotBase.hpp:72
Clear the flag that indicates a communication timeout between the EtherCAT master and the controller...
quantity< plane_angle > angle
Definition: JointData.hpp:90
virtual bool sendProcessData()=0
YouBotJoint & getBaseJoint(const unsigned int baseJointNumber)
Definition: YouBotBase.cpp:110
#define LOG(level)
Definition: Logger.hpp:102
virtual void AutomaticReceiveOn(const bool enableAutomaticReceive)=0
virtual bool receiveProcessData()=0
void getBasePosition(quantity< si::length > &longitudinalPosition, quantity< si::length > &transversalPosition, quantity< plane_angle > &orientation)
Definition: YouBotBase.cpp:123
the gear ratio which is needed for the calculations in the youBot driver
virtual void setJointData(const std::vector< JointAngleSetpoint > &JointData)
Definition: YouBotBase.cpp:250
void setParameter(const double parameter)
void setBasePosition(const quantity< si::length > &longitudinalPosition, const quantity< si::length > &transversalPosition, const quantity< plane_angle > &orientation)
Definition: YouBotBase.cpp:150
inverse the joint movement direction
quantity< si::angular_velocity > angularVelocity
Definition: JointData.hpp:114
virtual void cartesianPositionToWheelPositions(const quantity< si::length > &longitudinalPosition, const quantity< si::length > &transversalPosition, const quantity< plane_angle > &orientation, std::vector< quantity< plane_angle > > &wheelPositions)
#define SLEEP_MILLISEC(millisec)
Definition: Time.hpp:60
virtual ~YouBotBase()
Definition: YouBotBase.cpp:84
void setBaseVelocity(const quantity< si::velocity > &longitudinalVelocity, const quantity< si::velocity > &transversalVelocity, const quantity< si::angular_velocity > &angularVelocity)
Definition: YouBotBase.cpp:223
boost::scoped_ptr< ConfigFile > configfile
Definition: YouBotBase.hpp:172
void setParameter(const int lowerLimit, const int upperLimit, const bool activateLimits)
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)
void doJointCommutation()
does the sine commutation of the base joints
Definition: YouBotBase.cpp:95
Set-point current of the joint.
Definition: JointData.hpp:206
EthercatMasterInterface & ethercatMaster
Definition: YouBotBase.hpp:180
quantity< si::current > current
Definition: JointData.hpp:208
boost::ptr_vector< YouBotJoint > joints
Definition: YouBotBase.hpp:174
void initializeKinematic()
Definition: YouBotBase.cpp:690
static EthercatMasterInterface & getInstance(const std::string configFile="youbot-ethercat.cfg", const std::string configFilePath="../config/", const bool ethercatMasterWithThread=true)
FourSwedishWheelOmniBaseKinematic youBotBaseKinematic
This class represents the kinematic of the YouBot.
Definition: YouBotBase.hpp:114
Configuration for the base kinematic with four swedish wheels.
virtual void cartesianVelocityToWheelVelocities(const quantity< si::velocity > &longitudinalVelocity, const quantity< si::velocity > &transversalVelocity, const quantity< si::angular_velocity > &angularVelocity, std::vector< quantity< angular_velocity > > &wheelVelocities)
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
virtual void wheelPositionsToCartesianPosition(const std::vector< quantity< plane_angle > > &wheelPositions, quantity< si::length > &longitudinalPosition, quantity< si::length > &transversalPosition, quantity< plane_angle > &orientation)
Sensed position / angle of the joint.
Definition: JointData.hpp:88
quantity< plane_angle > angle
Definition: JointData.hpp:172
Set-point angle / position of the joint.
Definition: JointData.hpp:170
void getParameter(bool &parameter) const
Rounds per minute set-point of the joint.
Definition: JointData.hpp:194
Sensed velocity of the joint.
Definition: JointData.hpp:112


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