56 : ethercatMaster(
EthercatMaster::getInstance(
"youbot-ethercat.cfg", configFilePath)) {
    67     filename.append(
".cfg");
    87                         for (
unsigned int i = 0; i < 
BASEJOINTS; i++) {
   103     throw std::runtime_error(
"Unable to commutate joints - Unsupported firmware version!");
   112     if (baseJointNumber <= 0 || baseJointNumber > 
BASEJOINTS) {
   113       throw std::out_of_range(
"Invalid Joint Number");
   115     return joints[baseJointNumber - 1];
   123 void YouBotBase::getBasePosition(quantity<si::length>& longitudinalPosition, quantity<si::length>& transversalPosition, quantity<plane_angle>& orientation) {
   126     std::vector<quantity<plane_angle> > wheelPositions;
   127     quantity<plane_angle> dummy;
   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;
   150 void YouBotBase::setBasePosition(
const quantity<si::length>& longitudinalPosition, 
const quantity<si::length>& transversalPosition, 
const quantity<plane_angle>& orientation) {
   153     std::vector<quantity<plane_angle> > wheelPositions;
   154     quantity<plane_angle> dummy;
   162       throw std::out_of_range(
"To less wheel velocities");
   164     joints[0].setEncoderToZero();
   165     joints[1].setEncoderToZero();
   166     joints[2].setEncoderToZero();
   167     joints[3].setEncoderToZero();
   171     joints[0].getData(sensedPos);
   172     setpointPos.
angle = sensedPos.
angle + wheelPositions[0];
   173     joints[0].setData(setpointPos);
   175     joints[1].getData(sensedPos);
   176     setpointPos.
angle = sensedPos.
angle + wheelPositions[1];
   177     joints[1].setData(setpointPos);
   179     joints[2].getData(sensedPos);
   180     setpointPos.
angle = sensedPos.
angle + wheelPositions[2];
   181     joints[2].setData(setpointPos);
   183     joints[3].getData(sensedPos);
   184     setpointPos.
angle = sensedPos.
angle + wheelPositions[3];
   185     joints[3].setData(setpointPos);
   195 void YouBotBase::getBaseVelocity(quantity<si::velocity>& longitudinalVelocity, quantity<si::velocity>& transversalVelocity, quantity<si::angular_velocity>& angularVelocity) {
   198     std::vector<quantity<angular_velocity> > wheelVelocities;
   199     quantity<angular_velocity> dummy;
   204     joints[0].getData(sensedVel);
   206     joints[1].getData(sensedVel);
   208     joints[2].getData(sensedVel);
   210     joints[3].getData(sensedVel);
   223 void YouBotBase::setBaseVelocity(
const quantity<si::velocity>& longitudinalVelocity, 
const quantity<si::velocity>& transversalVelocity, 
const quantity<si::angular_velocity>& angularVelocity) {
   226     std::vector<quantity<angular_velocity> > wheelVelocities;
   232       throw std::out_of_range(
"To less wheel velocities");
   236     joints[0].setData(setVel);
   238     joints[1].setData(setVel);
   240     joints[2].setData(setVel);
   242     joints[3].setData(setVel);
   253       throw std::out_of_range(
"Wrong number of JointAngleSetpoints");
   256     joints[0].setData(JointData[0]);
   257     joints[1].setData(JointData[1]);
   258     joints[2].setData(JointData[2]);
   259     joints[3].setData(JointData[3]);
   272     joints[0].getData(data[0]);
   273     joints[1].getData(data[1]);
   274     joints[2].getData(data[2]);
   275     joints[3].getData(data[3]);
   286       throw std::out_of_range(
"Wrong number of JointVelocitySetpoints");
   289     joints[0].setData(JointData[0]);
   290     joints[1].setData(JointData[1]);
   291     joints[2].setData(JointData[2]);
   292     joints[3].setData(JointData[3]);
   304     joints[0].getData(data[0]);
   305     joints[1].getData(data[1]);
   306     joints[2].getData(data[2]);
   307     joints[3].getData(data[3]);
   318       throw std::out_of_range(
"Wrong number of JointCurrentSetpoint");
   321     joints[0].setData(JointData[0]);
   322     joints[1].setData(JointData[1]);
   323     joints[2].setData(JointData[2]);
   324     joints[3].setData(JointData[3]);
   336     joints[0].getData(data[0]);
   337     joints[1].getData(data[1]);
   338     joints[2].getData(data[2]);
   339     joints[3].getData(data[3]);
   350       throw std::out_of_range(
"Wrong number of JointTorqueSetpoint");
   353     joints[0].setData(JointData[0]);
   354     joints[1].setData(JointData[1]);
   355     joints[2].setData(JointData[2]);
   356     joints[3].setData(JointData[3]);
   368     joints[0].getData(data[0]);
   369     joints[1].getData(data[1]);
   370     joints[2].getData(data[2]);
   371     joints[3].getData(data[3]);
   382     int noInitialization = 0;
   383     std::string jointName;
   384     unsigned int statusFlags;
   385     std::vector<bool> isCommutated;
   389     zerocurrent.
current = 0.0 * ampere;
   393     for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   397     for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   401       if (!isInitialized) {
   406     if (noInitialization != 0) {
   407       LOG(
info) << 
"Base Joint Commutation with firmware 2.0";
   422       for (u = 1; u <= 5000; u++) {
   423         for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   426             isCommutated[i - 1] = 
true;
   434         if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3]) {
   440       for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   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);
   466     int noInitialization = 0;
   467     std::string jointName;
   471     for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   475     for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   479       if (!isInitialized) {
   484     if (noInitialization != 0) {
   485       LOG(
info) << 
"Base Joint Commutation with firmware 1.48";
   495       unsigned int statusFlags;
   496       std::vector<bool> isCommutated;
   501       for (u = 1; u <= 5000; u++) {
   502         for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   509             isCommutated[i - 1] = 
true;
   512         if (isCommutated[0] && isCommutated[1] && isCommutated[2] && isCommutated[3]) {
   520       for (
unsigned int i = 1; i <= 
BASEJOINTS; i++) {
   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);
   540     LOG(
trace) << 
"Initializing Joints";
   546       throw std::out_of_range(
"Not enough ethercat slaves were found to create a YouBotBase!");
   554     unsigned int slaveNumber = 0;
   555     configfile->readInto(slaveNumber, 
"JointTopology", 
"BaseLeftFront");
   556     if (slaveNumber <= noSlaves) {
   559       throw std::out_of_range(
"The ethercat slave number is not available!");
   562     configfile->readInto(slaveNumber, 
"JointTopology", 
"BaseRightFront");
   563     if (slaveNumber <= noSlaves) {
   566       throw std::out_of_range(
"The ethercat slave number is not available!");
   569     configfile->readInto(slaveNumber, 
"JointTopology", 
"BaseLeftBack");
   570     if (slaveNumber <= noSlaves) {
   573       throw std::out_of_range(
"The ethercat slave number is not available!");
   576     configfile->readInto(slaveNumber, 
"JointTopology", 
"BaseRightBack");
   577     if (slaveNumber <= noSlaves) {
   580       throw std::out_of_range(
"The ethercat slave number is not available!");
   585     std::string jointName;
   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;
   598     for (
unsigned int i = 0; i < 
BASEJOINTS; i++) {
   599       std::stringstream jointNameStream;
   600       jointNameStream << 
"Joint_" << i + 1;
   601       jointName = jointNameStream.str();
   604       joints[i].getConfigurationParameter(firmwareTypeVersion);
   607       std::string firmwareVersion;
   608       firmwareTypeVersion.
getParameter(controllerType, firmwareVersion);
   611       configfile->readInto(name, jointName, 
"JointName");
   614       LOG(
info) << name << 
"\t Controller Type: " << controllerType << 
"  Firmware version: " << firmwareVersion;
   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());
   623       bool isfirmwareSupported = 
false;
   626           isfirmwareSupported = 
true;
   631       if(!isfirmwareSupported){
   632         throw std::runtime_error(
"Unsupported firmware version: "+ firmwareVersion);
   640          throw std::runtime_error(
"All joints must have the same firmware version!");
   643       configfile->readInto(gearRatio_numerator, jointName, 
"GearRatio_numerator");
   644       configfile->readInto(gearRatio_denominator, jointName, 
"GearRatio_denominator");
   645       gearRatio.
setParameter(gearRatio_numerator / gearRatio_denominator);
   647       configfile->readInto(ticks, jointName, 
"EncoderTicksPerRound");
   650       double torqueConstant;
   651       configfile->readInto(torqueConstant, jointName, 
"TorqueConstant_[newton_meter_divided_by_ampere]");
   655       configfile->readInto(invdir, jointName, 
"InverseMovementDirection");
   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);
   664       long upperlimit = 0, lowerlimit = 0;
   665       configfile->readInto(lowerlimit, jointName, 
"LowerLimit_[encoderTicks]");
   666       configfile->readInto(upperlimit, jointName, 
"UpperLimit_[encoderTicks]");
   669       joints[i].setConfigurationParameter(jLimits);
   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);
   698     configfile->readInto(dummy, 
"YouBotKinematic", 
"LengthBetweenFrontAndRearWheels_[meter]");
   700     configfile->readInto(dummy, 
"YouBotKinematic", 
"LengthBetweenFrontWheels_[meter]");
   702     configfile->readInto(dummy, 
"YouBotKinematic", 
"WheelRadius_[meter]");
 YouBotBase(const std::string name, const std::string configFilePath="../config/")
void setParameter(const unsigned int parameter)
int alternativeControllerType
std::string actualFirmwareVersionAllJoints
the firmware version of the joint 
std::vector< std::string > supportedFirmwareVersions
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 ¶meter)
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
quantity< angular_velocity > angularVelocity
quantity< si::length > wheelRadius
void setParameter(const double parameter)
void commutationFirmware200()
does the commutation of the arm joints with firmware 2.0 
void setParameter(const bool parameter)
ROSCPP_DECL bool isInitialized()
Set-point velocity of the joint. 
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)
virtual void setConfigurationParameter(const JointParameter ¶meter)
Reads and writes a configuration file. 
void setConfiguration(const FourSwedishWheelOmniBaseKinematicConfiguration &configuration)
void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
void registerJointTrajectoryController(JointTrajectoryController *object, const unsigned int JointNumber)
void getBaseVelocity(quantity< si::velocity > &longitudinalVelocity, quantity< si::velocity > &transversalVelocity, quantity< si::angular_velocity > &angularVelocity)
void commutationFirmware148()
does the commutation of the arm joints with firmware 1.48 and below 
EthercatMasterWithThread * ethercatMasterWithThread
#define BASEJOINTS
The number of base joints. 
Clear the flag that indicates a communication timeout between the EtherCAT master and the controller...
quantity< plane_angle > angle
virtual bool sendProcessData()=0
YouBotJoint & getBaseJoint(const unsigned int baseJointNumber)
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)
the gear ratio which is needed for the calculations in the youBot driver 
virtual void setJointData(const std::vector< JointAngleSetpoint > &JointData)
void setParameter(const double parameter)
void setBasePosition(const quantity< si::length > &longitudinalPosition, const quantity< si::length > &transversalPosition, const quantity< plane_angle > &orientation)
inverse the joint movement direction 
quantity< si::angular_velocity > angularVelocity
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)
void setBaseVelocity(const quantity< si::velocity > &longitudinalVelocity, const quantity< si::velocity > &transversalVelocity, const quantity< si::angular_velocity > &angularVelocity)
virtual bool isThreadActive()=0
boost::scoped_ptr< ConfigFile > configfile
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 
quantity< si::length > lengthBetweenFrontAndRearWheels
void setParameter(const bool parameter)
void doJointCommutation()
does the sine commutation of the base joints 
Set-point current of the joint. 
EthercatMasterInterface & ethercatMaster
quantity< si::current > current
boost::ptr_vector< YouBotJoint > joints
void initializeKinematic()
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. 
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 
quantity< si::length > lengthBetweenFrontWheels
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. 
quantity< plane_angle > angle
Set-point angle / position of the joint. 
void getParameter(bool ¶meter) const 
Rounds per minute set-point of the joint. 
Sensed velocity of the joint.