57 : ethercatMaster(
EthercatMaster::getInstance(
"youbot-ethercat.cfg", configFilePath)) {
69 filename.append(
".cfg");
106 throw std::runtime_error(
"Unable to commutate joints - Unsupported firmware version!");
116 std::vector<JointRoundsPerMinuteSetpoint> calibrationVel;
120 std::vector<quantity<si::current> > maxCurrent;
121 quantity<si::current> tempdummy2;
123 std::vector<bool> doCalibration;
125 std::string jointName;
149 std::stringstream jointNameStream;
150 jointNameStream <<
"Joint_" << i + 1;
151 jointName = jointNameStream.str();
153 configfile->readInto(calib, jointName,
"DoCalibration");
154 doCalibration[i] = calib;
156 joints[i].getConfigurationParameter(IsCalibratedReadMessage);
158 doCalibration[i] =
false;
161 if (forceCalibration) {
162 doCalibration[i] =
true;
165 configfile->readInto(dummy, jointName,
"CalibrationMaxCurrent_[ampere]");
166 maxCurrent[i] = dummy * ampere;
167 std::string direction;
168 configfile->readInto(direction, jointName,
"CalibrationDirection");
170 joints[i].getConfigurationParameter(gearRatio);
171 double gearratio = 1;
174 if (direction ==
"POSITIV") {
175 calibrationVel[i].rpm = 1 / gearratio;
176 }
else if (direction ==
"NEGATIV") {
177 calibrationVel[i].rpm = -1 / gearratio;
179 throw std::runtime_error(
"Wrong calibration direction for " + jointName);
184 LOG(
info) <<
"Calibrate Manipulator Joints ";
186 std::vector<bool> finished;
187 finished.assign(numberArmJoints,
false);
194 if (doCalibration[i] ==
true) {
195 joints[i].setData(calibrationVel[i]);
209 while (numberUnfinished > 0) {
215 joints[i].getData(sensedCurrent);
217 if (abs(sensedCurrent.
current) > abs(maxCurrent[i])) {
220 currentStopMovement.
current = 0 * ampere;
221 joints[i].setData(currentStopMovement);
239 if (doCalibration[i] ==
true) {
241 joints[i].setEncoderToZero();
247 joints[i].setConfigurationParameter(IsCalibratedSetMessage);
255 long upperlimit = 0, lowerlimit = 0;
256 std::stringstream jointNameStream;
257 bool inverted =
false;
258 jointNameStream <<
"Joint_" << i + 1;
259 jointName = jointNameStream.str();
261 configfile->readInto(lowerlimit, jointName,
"LowerLimit_[encoderTicks]");
262 configfile->readInto(upperlimit, jointName,
"UpperLimit_[encoderTicks]");
263 configfile->readInto(inverted, jointName,
"InverseMovementDirection");
272 joints[i].setConfigurationParameter(jLimits);
282 bool doCalibration =
true;
283 configfile->readInto(doCalibration,
"Gripper",
"DoCalibration");
287 gripper->setConfigurationParameter(calibrate);
307 throw std::out_of_range(
"Invalid Joint Number");
309 return joints[armJointNumber - 1];
316 throw std::runtime_error(
"The gripper is disabled!");
328 throw std::out_of_range(
"Wrong number of JointAngleSetpoints");
332 joints[i].setData(JointData[i]);
346 joints[i].getData(data[i]);
357 throw std::out_of_range(
"Wrong number of JointVelocitySetpoints");
361 joints[i].setData(JointData[i]);
374 joints[i].getData(data[i]);
385 throw std::out_of_range(
"Wrong number of JointCurrentSetpoint");
389 joints[i].setData(JointData[i]);
402 joints[i].getData(data[i]);
413 throw std::out_of_range(
"Wrong number of JointTorqueSetpoint");
417 joints[i].setData(JointData[i]);
430 joints[i].getData(data[i]);
441 int noInitialization = 0;
442 std::string jointName;
443 unsigned int statusFlags;
444 std::vector<bool> isCommutated;
448 zerocurrent.
current = 0.0 * ampere;
460 if (!isInitialized) {
465 if (noInitialization != 0) {
466 LOG(
info) <<
"Manipulator Joint Commutation";
478 for (u = 1; u <= 5000; u++) {
482 isCommutated[i - 1] =
true;
490 if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3] && isCommutated[4]) {
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);
522 int noInitialization = 0;
523 std::string jointName;
535 if (!isInitialized) {
540 if (noInitialization != 0) {
541 LOG(
info) <<
"Manipulator Joint Commutation";
549 unsigned int statusFlags;
550 std::vector<bool> isCommutated;
555 for (u = 1; u <= 5000; u++) {
563 isCommutated[i - 1] =
true;
566 if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3] && isCommutated[4]) {
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);
597 if (
configfile->keyExists(
"JointTopology",
"NumberJoints"))
604 throw std::runtime_error(
"Not enough ethercat slaves were found to create a YouBotManipulator!");
607 unsigned int slaveNumber = 0;
609 std::stringstream jointConfigNameStream;
610 jointConfigNameStream <<
"ManipulatorJoint" << i;
611 std::string jointConfigName = jointConfigNameStream.str();
613 configfile->readInto(slaveNumber,
"JointTopology", jointConfigName);
614 if (slaveNumber <= noSlaves) {
617 throw std::out_of_range(
"The ethercat slave number is not available!");
622 std::string jointName;
627 double gearRatio_numerator = 0;
628 double gearRatio_denominator = 1;
631 double trajectory_p=0, trajectory_i=0, trajectory_d=0, trajectory_imax=0, trajectory_imin=0;
635 std::stringstream jointNameStream;
636 jointNameStream <<
"Joint_" << i + 1;
637 jointName = jointNameStream.str();
640 joints[i].getConfigurationParameter(firmwareTypeVersion);
643 std::string firmwareVersion;
644 firmwareTypeVersion.
getParameter(controllerType, firmwareVersion);
647 configfile->readInto(name, jointName,
"JointName");
650 LOG(
info) << name <<
"\t Controller Type: " << controllerType <<
" Firmware version: " << firmwareVersion;
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());
659 bool isfirmwareSupported =
false;
662 isfirmwareSupported =
true;
667 if(!isfirmwareSupported){
668 throw std::runtime_error(
"Unsupported firmware version: " + firmwareVersion);
676 throw std::runtime_error(
"All joints must have the same firmware version!");
679 configfile->readInto(gearRatio_numerator, jointName,
"GearRatio_numerator");
680 configfile->readInto(gearRatio_denominator, jointName,
"GearRatio_denominator");
681 gearRatio.
setParameter(gearRatio_numerator / gearRatio_denominator);
683 configfile->readInto(ticks, jointName,
"EncoderTicksPerRound");
686 double torqueConstant;
687 configfile->readInto(torqueConstant, jointName,
"TorqueConstant_[newton_meter_divided_by_ampere]");
691 configfile->readInto(invdir, jointName,
"InverseMovementDirection");
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);
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);
721 configfile->readInto(slaveNumber,
"JointTopology",
"ManipulatorJoint5");
729 double firmwareVersion;
733 this->
gripper->getConfigurationParameter(gripperVersion);
734 gripperVersion.
getParameter(controllerType, firmwareVersion);
736 LOG(
info) <<
"Gripper" <<
"\t\t Controller Type: " << controllerType <<
" Firmware version: " << firmwareVersion;
739 configfile->readInto(barname,
"GripperBar1",
"BarName");
741 this->
gripper->getGripperBar1().setConfigurationParameter(BarName);
743 configfile->readInto(dummy,
"GripperBar1",
"BarSpacingOffset_[meter]");
745 this->
gripper->getGripperBar1().setConfigurationParameter(barOffest);
747 configfile->readInto(dummy,
"GripperBar1",
"MaxTravelDistance_[meter]");
749 this->
gripper->getGripperBar1().setConfigurationParameter(maxDistance);
752 configfile->readInto(maxenc,
"GripperBar1",
"MaxEncoderValue");
754 this->
gripper->getGripperBar1().setConfigurationParameter(maxEncoder);
756 int stallThreshold = 0;
757 configfile->readInto(stallThreshold,
"GripperBar1",
"StallGuard2Threshold");
760 this->
gripper->getGripperBar1().setConfigurationParameter(threshold);
762 bool stallGuardFilter =
false;
763 configfile->readInto(stallGuardFilter,
"GripperBar1",
"StallGuard2FilterEnable");
766 this->
gripper->getGripperBar1().setConfigurationParameter(filter);
769 configfile->readInto(barname,
"GripperBar2",
"BarName");
771 this->
gripper->getGripperBar2().setConfigurationParameter(BarName);
773 configfile->readInto(dummy,
"GripperBar2",
"BarSpacingOffset_[meter]");
775 this->
gripper->getGripperBar2().setConfigurationParameter(barOffest);
777 configfile->readInto(dummy,
"GripperBar2",
"MaxTravelDistance_[meter]");
779 this->
gripper->getGripperBar2().setConfigurationParameter(maxDistance);
781 configfile->readInto(maxenc,
"GripperBar2",
"MaxEncoderValue");
783 this->
gripper->getGripperBar2().setConfigurationParameter(maxEncoder);
785 configfile->readInto(stallThreshold,
"GripperBar2",
"StallGuard2Threshold");
787 this->
gripper->getGripperBar2().setConfigurationParameter(threshold);
789 configfile->readInto(stallGuardFilter,
"GripperBar2",
"StallGuard2FilterEnable");
791 this->
gripper->getGripperBar2().setConfigurationParameter(filter);
792 }
catch (std::exception &e) {
void setParameter(const quantity< si::length > ¶meter)
YouBotGripper & getArmGripper()
void doJointCommutation()
does the sine commutation of the arm joints
void setParameter(const unsigned int parameter)
void setParameter(const quantity< si::length > ¶meter)
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 ...
virtual ~YouBotManipulator()
The Ethercat Master factory.
virtual void getConfigurationParameter(JointParameter ¶meter)
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
The encoder value when the gripper has reached it'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 ¶meter)
Reads and writes a configuration file.
std::string actualFirmwareVersionAllJoints
mailboxInputBuffer stctInput
void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
The youBot gripper with one degree of freedom.
void registerJointTrajectoryController(JointTrajectoryController *object, const unsigned int JointNumber)
void calibrateManipulator(const bool forceCalibration=false)
calibrate the reference position of the arm joints
mailboxOutputBuffer stctOutput
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 ¶meter) const
virtual bool sendProcessData()=0
boost::ptr_vector< YouBotJoint > joints
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.
encoder ticks setpoint of the joint
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)
the firmware version of the gripper
virtual bool isThreadActive()=0
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.
The name for a gripper bar or finger.
void setParameter(const bool parameter)
quantity< si::current > current
#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
int alternativeControllerType
void setParameter(const unsigned int parameter)
quantity< si::current > current
virtual unsigned int getNumberOfSlaves() const =0
return the quantity of ethercat slave which have an input/output buffer
abstract data class for joints
unsigned int numberArmJoints
bool isGripperInitialized
void getParameter(bool ¶meter) const
Rounds per minute set-point of the joint.