YouBotJointParameterPasswordProtected.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2011
00004  * All rights reserved.
00005  *
00006  * Hochschule Bonn-Rhein-Sieg
00007  * University of Applied Sciences
00008  * Computer Science Department
00009  *
00010  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00011  *
00012  * Author:
00013  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
00014  * Supervised by:
00015  * Gerhard K. Kraetzschmar
00016  *
00017  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00018  *
00019  * This sofware is published under a dual-license: GNU Lesser General Public 
00020  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
00021  * code may choose which terms they prefer.
00022  *
00023  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024  *
00025  * Redistribution and use in source and binary forms, with or without
00026  * modification, are permitted provided that the following conditions are met:
00027  *
00028  *     * Redistributions of source code must retain the above copyright
00029  *       notice, this list of conditions and the following disclaimer.
00030  *     * Redistributions in binary form must reproduce the above copyright
00031  *       notice, this list of conditions and the following disclaimer in the
00032  *       documentation and/or other materials provided with the distribution.
00033  *     * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
00034  *       contributors may be used to endorse or promote products derived from
00035  *       this software without specific prior written permission.
00036  *
00037  * This program is free software: you can redistribute it and/or modify
00038  * it under the terms of the GNU Lesser General Public License LGPL as
00039  * published by the Free Software Foundation, either version 2.1 of the
00040  * License, or (at your option) any later version or the BSD license.
00041  *
00042  * This program is distributed in the hope that it will be useful,
00043  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00044  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00045  * GNU Lesser General Public License LGPL and the BSD license for more details.
00046  *
00047  * You should have received a copy of the GNU Lesser General Public
00048  * License LGPL and BSD license along with this program.
00049  *
00050  ****************************************************************/
00051 #include <youbot_driver/youbot/YouBotJointParameterPasswordProtected.hpp>
00052 namespace youbot
00053 {
00054 
00055 YouBotJointParameterPasswordProtected::YouBotJointParameterPasswordProtected()
00056 {
00057   // Bouml preserved body begin 000A4CF1
00058   // Bouml preserved body end 000A4CF1
00059 }
00060 
00061 YouBotJointParameterPasswordProtected::~YouBotJointParameterPasswordProtected()
00062 {
00063   // Bouml preserved body begin 000A4D71
00064   // Bouml preserved body end 000A4D71
00065 }
00066 
00067 ActivateOvervoltageProtection::ActivateOvervoltageProtection()
00068 {
00069   // Bouml preserved body begin 00083371
00070   this->name = "ActivateOvervoltageProtection";
00071   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00072   // Bouml preserved body end 00083371
00073 }
00074 
00075 ActivateOvervoltageProtection::~ActivateOvervoltageProtection()
00076 {
00077   // Bouml preserved body begin 000833F1
00078   // Bouml preserved body end 000833F1
00079 }
00080 
00081 void ActivateOvervoltageProtection::getParameter(bool& parameter) const
00082 {
00083   // Bouml preserved body begin 00083471
00084   parameter = this->value;
00085   // Bouml preserved body end 00083471
00086 }
00087 
00088 void ActivateOvervoltageProtection::setParameter(const bool parameter)
00089 {
00090   // Bouml preserved body begin 000834F1
00091   this->value = parameter;
00092   // Bouml preserved body end 000834F1
00093 }
00094 
00095 void ActivateOvervoltageProtection::toString(std::string& value)
00096 {
00097   // Bouml preserved body begin 0009E4F1
00098   std::stringstream ss;
00099   ss << this->name << ": " << this->value;
00100   value = ss.str();
00101   // Bouml preserved body end 0009E4F1
00102 }
00103 
00104 void ActivateOvervoltageProtection::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00105                                                         const YouBotJointStorage& storage) const
00106 {
00107   // Bouml preserved body begin 00083571
00108 
00109   message.stctOutput.commandNumber = msgType;
00110   message.stctOutput.moduleAddress = DRIVE;
00111   message.stctOutput.typeNumber = 245; //ActivateOvervoltageProtection
00112   message.stctOutput.value = value;
00113 
00114   // Bouml preserved body end 00083571
00115 }
00116 
00117 void ActivateOvervoltageProtection::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00118                                                         const YouBotJointStorage& storage)
00119 {
00120   // Bouml preserved body begin 000835F1
00121   this->value = message.stctInput.value;
00122   // Bouml preserved body end 000835F1
00123 }
00124 
00125 ActualCommutationOffset::ActualCommutationOffset()
00126 {
00127   // Bouml preserved body begin 0007D871
00128   this->name = "ActualCommutationOffset";
00129   this->lowerLimit = INT_MIN;
00130   this->upperLimit = INT_MAX;
00131   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00132   // Bouml preserved body end 0007D871
00133 }
00134 
00135 ActualCommutationOffset::~ActualCommutationOffset()
00136 {
00137   // Bouml preserved body begin 0007D8F1
00138   // Bouml preserved body end 0007D8F1
00139 }
00140 
00141 void ActualCommutationOffset::getParameter(int& parameter) const
00142 {
00143   // Bouml preserved body begin 0007D971
00144   parameter = this->value;
00145   // Bouml preserved body end 0007D971
00146 }
00147 
00148 void ActualCommutationOffset::setParameter(const int parameter)
00149 {
00150   // Bouml preserved body begin 0007D9F1
00151   if (this->lowerLimit > parameter)
00152   {
00153     throw std::out_of_range("The parameter exceeds the lower limit");
00154   }
00155   if (this->upperLimit < parameter)
00156   {
00157     throw std::out_of_range("The parameter exceeds the upper limit");
00158   }
00159 
00160   this->value = parameter;
00161   // Bouml preserved body end 0007D9F1
00162 }
00163 
00164 void ActualCommutationOffset::toString(std::string& value)
00165 {
00166   // Bouml preserved body begin 0009D771
00167   std::stringstream ss;
00168   ss << this->name << ": " << this->value;
00169   value = ss.str();
00170   // Bouml preserved body end 0009D771
00171 }
00172 
00173 void ActualCommutationOffset::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00174                                                   const YouBotJointStorage& storage) const
00175 {
00176   // Bouml preserved body begin 0007DA71
00177 
00178   message.stctOutput.commandNumber = msgType;
00179   message.stctOutput.moduleAddress = DRIVE;
00180   message.stctOutput.typeNumber = 165; //ActualCommutationOffset
00181   message.stctOutput.value = value;
00182 
00183   // Bouml preserved body end 0007DA71
00184 }
00185 
00186 void ActualCommutationOffset::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00187                                                   const YouBotJointStorage& storage)
00188 {
00189   // Bouml preserved body begin 0007DAF1
00190   this->value = (int32)message.stctInput.value;
00191   // Bouml preserved body end 0007DAF1
00192 }
00193 
00194 ApproveProtectedParameters::ApproveProtectedParameters()
00195 {
00196   // Bouml preserved body begin 000956F1
00197   this->name = "ApproveProtectedParameters";
00198   this->lowerLimit = INT_MIN;
00199   this->upperLimit = INT_MAX;
00200   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00201   // Bouml preserved body end 000956F1
00202 }
00203 
00204 ApproveProtectedParameters::~ApproveProtectedParameters()
00205 {
00206   // Bouml preserved body begin 00095771
00207   // Bouml preserved body end 00095771
00208 }
00209 
00210 void ApproveProtectedParameters::getParameter(int& parameter) const
00211 {
00212   // Bouml preserved body begin 000957F1
00213   parameter = this->value;
00214   // Bouml preserved body end 000957F1
00215 }
00216 
00217 void ApproveProtectedParameters::setParameter(const int parameter)
00218 {
00219   // Bouml preserved body begin 00095871
00220   if (this->lowerLimit > parameter)
00221   {
00222     throw std::out_of_range("The parameter exceeds the lower limit");
00223   }
00224   if (this->upperLimit < parameter)
00225   {
00226     throw std::out_of_range("The parameter exceeds the upper limit");
00227   }
00228   this->value = parameter;
00229   // Bouml preserved body end 00095871
00230 }
00231 
00232 void ApproveProtectedParameters::toString(std::string& value)
00233 {
00234   // Bouml preserved body begin 0009E671
00235   std::stringstream ss;
00236   ss << this->name << ": " << this->value;
00237   value = ss.str();
00238   // Bouml preserved body end 0009E671
00239 }
00240 
00241 void ApproveProtectedParameters::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00242                                                      const YouBotJointStorage& storage) const
00243 {
00244   // Bouml preserved body begin 000958F1
00245   message.stctOutput.commandNumber = msgType;
00246   message.stctOutput.moduleAddress = DRIVE;
00247   message.stctOutput.typeNumber = 248; //ApproveProtectedParameters
00248   message.stctOutput.value = value;
00249   // Bouml preserved body end 000958F1
00250 }
00251 
00252 void ApproveProtectedParameters::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00253                                                      const YouBotJointStorage& storage)
00254 {
00255   // Bouml preserved body begin 00095971
00256   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00257   {
00258     this->value = message.stctInput.value;
00259   }
00260   // Bouml preserved body end 00095971
00261 }
00262 
00263 BEMFConstant::BEMFConstant()
00264 {
00265   // Bouml preserved body begin 00082B71
00266   this->name = "BEMFConstant";
00267   this->lowerLimit = INT_MIN;
00268   this->upperLimit = INT_MAX;
00269   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00270   // Bouml preserved body end 00082B71
00271 }
00272 
00273 BEMFConstant::~BEMFConstant()
00274 {
00275   // Bouml preserved body begin 00082BF1
00276   // Bouml preserved body end 00082BF1
00277 }
00278 
00279 void BEMFConstant::getParameter(int& parameter) const
00280 {
00281   // Bouml preserved body begin 00082C71
00282   parameter = this->value;
00283   // Bouml preserved body end 00082C71
00284 }
00285 
00286 void BEMFConstant::setParameter(const int parameter)
00287 {
00288   // Bouml preserved body begin 00082CF1
00289   if (this->lowerLimit > parameter)
00290   {
00291     throw std::out_of_range("The parameter exceeds the lower limit");
00292   }
00293   if (this->upperLimit < parameter)
00294   {
00295     throw std::out_of_range("The parameter exceeds the upper limit");
00296   }
00297 
00298   this->value = parameter;
00299   // Bouml preserved body end 00082CF1
00300 }
00301 
00302 void BEMFConstant::toString(std::string& value)
00303 {
00304   // Bouml preserved body begin 0009E1F1
00305   std::stringstream ss;
00306   ss << this->name << ": " << this->value;
00307   value = ss.str();
00308   // Bouml preserved body end 0009E1F1
00309 }
00310 
00311 void BEMFConstant::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00312                                        const YouBotJointStorage& storage) const
00313 {
00314   // Bouml preserved body begin 00082D71
00315 
00316   message.stctOutput.commandNumber = msgType;
00317   message.stctOutput.moduleAddress = DRIVE;
00318   message.stctOutput.typeNumber = 239; //BEMFConstant
00319   message.stctOutput.value = value; //TODO do convertion
00320 
00321   // Bouml preserved body end 00082D71
00322 }
00323 
00324 void BEMFConstant::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00325 {
00326   // Bouml preserved body begin 00082DF1
00327   this->value = (int32)message.stctInput.value; //TODO do convertion
00328   // Bouml preserved body end 00082DF1
00329 }
00330 
00331 CommutationMode::CommutationMode()
00332 {
00333   // Bouml preserved body begin 000704F1
00334   this->name = "CommutationMode";
00335   this->lowerLimit = 0;
00336   this->upperLimit = 5;
00337   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00338   // Bouml preserved body end 000704F1
00339 }
00340 
00341 CommutationMode::~CommutationMode()
00342 {
00343   // Bouml preserved body begin 00070571
00344   // Bouml preserved body end 00070571
00345 }
00346 
00347 void CommutationMode::getParameter(unsigned int& parameter) const
00348 {
00349   // Bouml preserved body begin 000705F1
00350   parameter = this->value;
00351   // Bouml preserved body end 000705F1
00352 }
00353 
00354 void CommutationMode::setParameter(const unsigned int parameter)
00355 {
00356   // Bouml preserved body begin 00093471
00357   if (this->lowerLimit > parameter)
00358   {
00359     throw std::out_of_range("The parameter exceeds the lower limit");
00360   }
00361   if (this->upperLimit < parameter)
00362   {
00363     throw std::out_of_range("The parameter exceeds the upper limit");
00364   }
00365   this->value = parameter;
00366   // Bouml preserved body end 00093471
00367 }
00368 
00369 void CommutationMode::toString(std::string& value)
00370 {
00371   // Bouml preserved body begin 0009E7F1
00372   std::stringstream ss;
00373   ss << this->name << ": " << this->value;
00374   value = ss.str();
00375   // Bouml preserved body end 0009E7F1
00376 }
00377 
00378 void CommutationMode::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00379                                           const YouBotJointStorage& storage) const
00380 {
00381   // Bouml preserved body begin 00070671
00382   message.stctOutput.commandNumber = msgType;
00383   message.stctOutput.moduleAddress = DRIVE;
00384   message.stctOutput.typeNumber = 159; //CommutationMode
00385   message.stctOutput.value = value;
00386   // Bouml preserved body end 00070671
00387 }
00388 
00389 void CommutationMode::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00390 {
00391   // Bouml preserved body begin 000720F1
00392   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00393   {
00394     this->value = message.stctInput.value; //TODO do convertion
00395   }
00396   // Bouml preserved body end 000720F1
00397 }
00398 
00399 CommutationMotorCurrent::CommutationMotorCurrent()
00400 {
00401   // Bouml preserved body begin 0008C371
00402   this->name = "CommutationMotorCurrent";
00403   this->lowerLimit = 0 * ampere;
00404   this->upperLimit = INT_MAX * ampere;
00405   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00406   // Bouml preserved body end 0008C371
00407 }
00408 
00409 CommutationMotorCurrent::~CommutationMotorCurrent()
00410 {
00411   // Bouml preserved body begin 0008C3F1
00412   // Bouml preserved body end 0008C3F1
00413 }
00414 
00415 void CommutationMotorCurrent::getParameter(quantity<current>& parameter) const
00416 {
00417   // Bouml preserved body begin 0008C471
00418   parameter = this->value;
00419   // Bouml preserved body end 0008C471
00420 }
00421 
00422 void CommutationMotorCurrent::setParameter(const quantity<current>& parameter)
00423 {
00424   // Bouml preserved body begin 0008C4F1
00425   if (this->lowerLimit > parameter)
00426   {
00427     throw std::out_of_range("The parameter exceeds the lower limit");
00428   }
00429   if (this->upperLimit < parameter)
00430   {
00431     throw std::out_of_range("The parameter exceeds the upper limit");
00432   }
00433 
00434   this->value = parameter;
00435   // Bouml preserved body end 0008C4F1
00436 }
00437 
00438 void CommutationMotorCurrent::toString(std::string& value)
00439 {
00440   // Bouml preserved body begin 0009DCF1
00441   std::stringstream ss;
00442   ss << this->name << ": " << this->value;
00443   value = ss.str();
00444   // Bouml preserved body end 0009DCF1
00445 }
00446 
00447 void CommutationMotorCurrent::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00448                                                   const YouBotJointStorage& storage) const
00449 {
00450   // Bouml preserved body begin 0008C571
00451 
00452   message.stctOutput.commandNumber = msgType;
00453   message.stctOutput.moduleAddress = DRIVE;
00454   message.stctOutput.typeNumber = 177; //CommutationMotorCurrent
00455   message.stctOutput.value = (uint32)(value.value() * 1000.0); // ampere to milli ampere
00456 
00457   // Bouml preserved body end 0008C571
00458 }
00459 
00460 void CommutationMotorCurrent::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00461                                                   const YouBotJointStorage& storage)
00462 {
00463   // Bouml preserved body begin 0008C5F1
00464   double temp = (uint32)message.stctInput.value;
00465   this->value = temp / 1000.0 * ampere; //milli ampere to ampere
00466   // Bouml preserved body end 0008C5F1
00467 }
00468 
00469 CurrentControlLoopDelay::CurrentControlLoopDelay()
00470 {
00471   // Bouml preserved body begin 00079F71
00472   this->name = "CurrentControlLoopDelay";
00473   this->lowerLimit = 0;
00474   this->upperLimit = INT_MAX * seconds;
00475   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00476   // Bouml preserved body end 00079F71
00477 }
00478 
00479 CurrentControlLoopDelay::~CurrentControlLoopDelay()
00480 {
00481   // Bouml preserved body begin 00079FF1
00482   // Bouml preserved body end 00079FF1
00483 }
00484 
00485 void CurrentControlLoopDelay::getParameter(quantity<si::time>& parameter) const
00486 {
00487   // Bouml preserved body begin 0007A071
00488   parameter = this->value;
00489   // Bouml preserved body end 0007A071
00490 }
00491 
00492 void CurrentControlLoopDelay::setParameter(const quantity<si::time>& parameter)
00493 {
00494   // Bouml preserved body begin 0007A0F1
00495   if (this->lowerLimit > parameter)
00496   {
00497     throw std::out_of_range("The parameter exceeds the lower limit");
00498   }
00499   if (this->upperLimit < parameter)
00500   {
00501     throw std::out_of_range("The parameter exceeds the upper limit");
00502   }
00503 
00504   this->value = parameter;
00505   // Bouml preserved body end 0007A0F1
00506 }
00507 
00508 void CurrentControlLoopDelay::toString(std::string& value)
00509 {
00510   // Bouml preserved body begin 0009CFF1
00511   std::stringstream ss;
00512   ss << this->name << ": " << this->value;
00513   value = ss.str();
00514   // Bouml preserved body end 0009CFF1
00515 }
00516 
00517 void CurrentControlLoopDelay::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00518                                                   const YouBotJointStorage& storage) const
00519 {
00520   // Bouml preserved body begin 0007A171
00521 
00522   message.stctOutput.commandNumber = msgType;
00523   message.stctOutput.moduleAddress = DRIVE;
00524   message.stctOutput.typeNumber = 134; //CurrentControlLoopDelay
00525   message.stctOutput.value = (uint32)(value.value() * 1000 * 1000 / 50.0); //sec to µsec
00526 
00527   // Bouml preserved body end 0007A171
00528 }
00529 
00530 void CurrentControlLoopDelay::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00531                                                   const YouBotJointStorage& storage)
00532 {
00533   // Bouml preserved body begin 0007A1F1
00534   double temp = (uint32)message.stctInput.value;
00535   this->value = (temp / (1000.0 * 1000.0)) * 50 * seconds; //µsec to sec
00536   // Bouml preserved body end 0007A1F1
00537 }
00538 
00539 EncoderResolution::EncoderResolution()
00540 {
00541   // Bouml preserved body begin 000713F1
00542   this->name = "EncoderResolution";
00543   this->lowerLimit = 0;
00544   this->upperLimit = INT_MAX;
00545   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00546   // Bouml preserved body end 000713F1
00547 }
00548 
00549 EncoderResolution::~EncoderResolution()
00550 {
00551   // Bouml preserved body begin 00071471
00552   // Bouml preserved body end 00071471
00553 }
00554 
00555 void EncoderResolution::getParameter(unsigned int& parameter) const
00556 {
00557   // Bouml preserved body begin 000714F1
00558   parameter = this->value;
00559   // Bouml preserved body end 000714F1
00560 }
00561 
00562 void EncoderResolution::setParameter(const unsigned int parameter)
00563 {
00564   // Bouml preserved body begin 00093671
00565   if (this->lowerLimit > parameter)
00566   {
00567     throw std::out_of_range("The parameter exceeds the lower limit");
00568   }
00569   if (this->upperLimit < parameter)
00570   {
00571     throw std::out_of_range("The parameter exceeds the upper limit");
00572   }
00573   this->value = parameter;
00574   // Bouml preserved body end 00093671
00575 }
00576 
00577 void EncoderResolution::toString(std::string& value)
00578 {
00579   // Bouml preserved body begin 0009E9F1
00580   std::stringstream ss;
00581   ss << this->name << ": " << this->value;
00582   value = ss.str();
00583   // Bouml preserved body end 0009E9F1
00584 }
00585 
00586 void EncoderResolution::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00587                                             const YouBotJointStorage& storage) const
00588 {
00589   // Bouml preserved body begin 00071571
00590   message.stctOutput.commandNumber = msgType;
00591   message.stctOutput.moduleAddress = DRIVE;
00592   message.stctOutput.typeNumber = 250; //EncoderResolution
00593   message.stctOutput.value = (uint32)value;
00594   // Bouml preserved body end 00071571
00595 }
00596 
00597 void EncoderResolution::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00598 {
00599   // Bouml preserved body begin 00072371
00600   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00601   {
00602     this->value = (uint32)message.stctInput.value;
00603   }
00604   // Bouml preserved body end 00072371
00605 }
00606 
00607 EncoderStopSwitch::EncoderStopSwitch()
00608 {
00609   // Bouml preserved body begin 0007D471
00610   this->name = "EncoderStopSwitch";
00611   this->lowerLimit = 0;
00612   this->upperLimit = 3;
00613   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00614   // Bouml preserved body end 0007D471
00615 }
00616 
00617 EncoderStopSwitch::~EncoderStopSwitch()
00618 {
00619   // Bouml preserved body begin 0007D4F1
00620   // Bouml preserved body end 0007D4F1
00621 }
00622 
00623 void EncoderStopSwitch::getParameter(unsigned int& parameter) const
00624 {
00625   // Bouml preserved body begin 0007D571
00626   parameter = this->value;
00627   // Bouml preserved body end 0007D571
00628 }
00629 
00630 void EncoderStopSwitch::setParameter(const unsigned int parameter)
00631 {
00632   // Bouml preserved body begin 0007D5F1
00633   if (this->lowerLimit > parameter)
00634   {
00635     throw std::out_of_range("The parameter exceeds the lower limit");
00636   }
00637   if (this->upperLimit < parameter)
00638   {
00639     throw std::out_of_range("The parameter exceeds the upper limit");
00640   }
00641 
00642   this->value = parameter;
00643   // Bouml preserved body end 0007D5F1
00644 }
00645 
00646 void EncoderStopSwitch::toString(std::string& value)
00647 {
00648   // Bouml preserved body begin 0009D6F1
00649   std::stringstream ss;
00650   ss << this->name << ": " << this->value;
00651   value = ss.str();
00652   // Bouml preserved body end 0009D6F1
00653 }
00654 
00655 void EncoderStopSwitch::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00656                                             const YouBotJointStorage& storage) const
00657 {
00658   // Bouml preserved body begin 0007D671
00659 
00660   message.stctOutput.commandNumber = msgType;
00661   message.stctOutput.moduleAddress = DRIVE;
00662   message.stctOutput.typeNumber = 164; //EncoderStopSwitch
00663   message.stctOutput.value = (uint32)value;
00664 
00665   // Bouml preserved body end 0007D671
00666 }
00667 
00668 void EncoderStopSwitch::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00669 {
00670   // Bouml preserved body begin 0007D6F1
00671   this->value = (uint32)message.stctInput.value;
00672   // Bouml preserved body end 0007D6F1
00673 }
00674 
00675 HallSensorPolarityReversal::HallSensorPolarityReversal()
00676 {
00677   // Bouml preserved body begin 00071CF1
00678   this->name = "HallSensorPolarityReversal";
00679   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00680   // Bouml preserved body end 00071CF1
00681 }
00682 
00683 HallSensorPolarityReversal::~HallSensorPolarityReversal()
00684 {
00685   // Bouml preserved body begin 00071D71
00686   // Bouml preserved body end 00071D71
00687 }
00688 
00689 void HallSensorPolarityReversal::getParameter(bool& parameter) const
00690 {
00691   // Bouml preserved body begin 00071DF1
00692   parameter = this->value;
00693   // Bouml preserved body end 00071DF1
00694 }
00695 
00696 void HallSensorPolarityReversal::setParameter(const bool parameter)
00697 {
00698   // Bouml preserved body begin 00093771
00699   this->value = parameter;
00700   // Bouml preserved body end 00093771
00701 }
00702 
00703 void HallSensorPolarityReversal::toString(std::string& value)
00704 {
00705   // Bouml preserved body begin 0009EAF1
00706   std::stringstream ss;
00707   ss << this->name << ": " << this->value;
00708   value = ss.str();
00709   // Bouml preserved body end 0009EAF1
00710 }
00711 
00712 void HallSensorPolarityReversal::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00713                                                      const YouBotJointStorage& storage) const
00714 {
00715   // Bouml preserved body begin 00071E71
00716   message.stctOutput.commandNumber = msgType;
00717   message.stctOutput.moduleAddress = DRIVE;
00718   message.stctOutput.typeNumber = 254; //HallSensorPolarityReversal
00719   message.stctOutput.value = (uint32)value;
00720   // Bouml preserved body end 00071E71
00721 }
00722 
00723 void HallSensorPolarityReversal::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00724                                                      const YouBotJointStorage& storage)
00725 {
00726   // Bouml preserved body begin 000724F1
00727   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00728   {
00729     this->value = (uint32)message.stctInput.value;
00730   }
00731   // Bouml preserved body end 000724F1
00732 }
00733 
00734 I2tExceedCounter::I2tExceedCounter()
00735 {
00736   // Bouml preserved body begin 000A1171
00737   this->name = "I2tExceedCounter";
00738   this->lowerLimit = 0;
00739   this->upperLimit = INT_MAX;
00740   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00741   // Bouml preserved body end 000A1171
00742 }
00743 
00744 I2tExceedCounter::~I2tExceedCounter()
00745 {
00746   // Bouml preserved body begin 000A11F1
00747   // Bouml preserved body end 000A11F1
00748 }
00749 
00750 void I2tExceedCounter::getParameter(unsigned int& parameter) const
00751 {
00752   // Bouml preserved body begin 000A1271
00753   parameter = this->value;
00754   // Bouml preserved body end 000A1271
00755 }
00756 
00757 void I2tExceedCounter::setParameter(const unsigned int parameter)
00758 {
00759   // Bouml preserved body begin 000A12F1
00760   if (this->lowerLimit > parameter)
00761   {
00762     throw std::out_of_range("The parameter exceeds the lower limit");
00763   }
00764   if (this->upperLimit < parameter)
00765   {
00766     throw std::out_of_range("The parameter exceeds the upper limit");
00767   }
00768   this->value = parameter;
00769   // Bouml preserved body end 000A12F1
00770 }
00771 
00772 void I2tExceedCounter::toString(std::string& value)
00773 {
00774   // Bouml preserved body begin 000A1371
00775   std::stringstream ss;
00776   ss << this->name << ": " << this->value;
00777   value = ss.str();
00778   // Bouml preserved body end 000A1371
00779 }
00780 
00781 void I2tExceedCounter::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00782                                            const YouBotJointStorage& storage) const
00783 {
00784   // Bouml preserved body begin 000A13F1
00785   message.stctOutput.commandNumber = msgType;
00786   message.stctOutput.moduleAddress = DRIVE;
00787   message.stctOutput.typeNumber = 28; //I2tExceedCounter
00788   message.stctOutput.value = (uint32)value;
00789   // Bouml preserved body end 000A13F1
00790 }
00791 
00792 void I2tExceedCounter::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00793 {
00794   // Bouml preserved body begin 000A1471
00795   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00796   {
00797     this->value = (uint32)message.stctInput.value;
00798   }
00799   // Bouml preserved body end 000A1471
00800 }
00801 
00802 I2tLimit::I2tLimit()
00803 {
00804   // Bouml preserved body begin 000A0871
00805   this->name = "I2tLimit";
00806   this->lowerLimit = 0;
00807   this->upperLimit = INT_MAX;
00808   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00809   // Bouml preserved body end 000A0871
00810 }
00811 
00812 I2tLimit::~I2tLimit()
00813 {
00814   // Bouml preserved body begin 000A08F1
00815   // Bouml preserved body end 000A08F1
00816 }
00817 
00818 void I2tLimit::getParameter(unsigned int& parameter) const
00819 {
00820   // Bouml preserved body begin 000A0971
00821   parameter = this->value;
00822   // Bouml preserved body end 000A0971
00823 }
00824 
00825 void I2tLimit::setParameter(const unsigned int parameter)
00826 {
00827   // Bouml preserved body begin 000A09F1
00828   if (this->lowerLimit > parameter)
00829   {
00830     throw std::out_of_range("The parameter exceeds the lower limit");
00831   }
00832   if (this->upperLimit < parameter)
00833   {
00834     throw std::out_of_range("The parameter exceeds the upper limit");
00835   }
00836   this->value = parameter;
00837   // Bouml preserved body end 000A09F1
00838 }
00839 
00840 void I2tLimit::toString(std::string& value)
00841 {
00842   // Bouml preserved body begin 000A0A71
00843   std::stringstream ss;
00844   ss << this->name << ": " << this->value;
00845   value = ss.str();
00846   // Bouml preserved body end 000A0A71
00847 }
00848 
00849 void I2tLimit::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00850                                    const YouBotJointStorage& storage) const
00851 {
00852   // Bouml preserved body begin 000A0AF1
00853   message.stctOutput.commandNumber = msgType;
00854   message.stctOutput.moduleAddress = DRIVE;
00855   message.stctOutput.typeNumber = 26; //I2tLimit
00856   message.stctOutput.value = (uint32)value;
00857   // Bouml preserved body end 000A0AF1
00858 }
00859 
00860 void I2tLimit::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00861 {
00862   // Bouml preserved body begin 000A0B71
00863   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00864   {
00865     this->value = (uint32)message.stctInput.value;
00866   }
00867   // Bouml preserved body end 000A0B71
00868 }
00869 
00870 InitializationMode::InitializationMode()
00871 {
00872   // Bouml preserved body begin 000710F1
00873   this->name = "InitializationMode";
00874   this->lowerLimit = 0;
00875   this->upperLimit = 2;
00876   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00877   // Bouml preserved body end 000710F1
00878 }
00879 
00880 InitializationMode::~InitializationMode()
00881 {
00882   // Bouml preserved body begin 00071171
00883   // Bouml preserved body end 00071171
00884 }
00885 
00886 void InitializationMode::getParameter(int& parameter) const
00887 {
00888   // Bouml preserved body begin 000711F1
00889   parameter = this->value;
00890   // Bouml preserved body end 000711F1
00891 }
00892 
00893 void InitializationMode::setParameter(const int parameter)
00894 {
00895   // Bouml preserved body begin 000935F1
00896   if (this->lowerLimit > parameter)
00897   {
00898     throw std::out_of_range("The parameter exceeds the lower limit");
00899   }
00900   if (this->upperLimit < parameter)
00901   {
00902     throw std::out_of_range("The parameter exceeds the upper limit");
00903   }
00904   this->value = parameter;
00905   // Bouml preserved body end 000935F1
00906 }
00907 
00908 void InitializationMode::toString(std::string& value)
00909 {
00910   // Bouml preserved body begin 0009E971
00911   std::stringstream ss;
00912   ss << this->name << ": " << this->value;
00913   value = ss.str();
00914   // Bouml preserved body end 0009E971
00915 }
00916 
00917 void InitializationMode::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00918                                              const YouBotJointStorage& storage) const
00919 {
00920   // Bouml preserved body begin 00071271
00921   message.stctOutput.commandNumber = msgType;
00922   message.stctOutput.moduleAddress = DRIVE;
00923   message.stctOutput.typeNumber = 249; //InitializationMode
00924   message.stctOutput.value = value;
00925   // Bouml preserved body end 00071271
00926 }
00927 
00928 void InitializationMode::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00929 {
00930   // Bouml preserved body begin 000722F1
00931   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00932   {
00933     this->value = (int32)message.stctInput.value;
00934   }
00935   // Bouml preserved body end 000722F1
00936 }
00937 
00938 InitSineDelay::InitSineDelay()
00939 {
00940   // Bouml preserved body begin 00082F71
00941   this->name = "InitSineDelay";
00942   this->lowerLimit = -32.768 * seconds;
00943   this->upperLimit = +32.767 * seconds;
00944   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00945   // Bouml preserved body end 00082F71
00946 }
00947 
00948 InitSineDelay::~InitSineDelay()
00949 {
00950   // Bouml preserved body begin 00082FF1
00951   // Bouml preserved body end 00082FF1
00952 }
00953 
00954 void InitSineDelay::getParameter(quantity<si::time>& parameter) const
00955 {
00956   // Bouml preserved body begin 00083071
00957   parameter = this->value;
00958   // Bouml preserved body end 00083071
00959 }
00960 
00961 void InitSineDelay::setParameter(const quantity<si::time>& parameter)
00962 {
00963   // Bouml preserved body begin 000830F1
00964   if (this->lowerLimit > parameter)
00965   {
00966     throw std::out_of_range("The parameter exceeds the lower limit");
00967   }
00968   if (this->upperLimit < parameter)
00969   {
00970     throw std::out_of_range("The parameter exceeds the upper limit");
00971   }
00972 
00973   this->value = parameter;
00974   // Bouml preserved body end 000830F1
00975 }
00976 
00977 void InitSineDelay::toString(std::string& value)
00978 {
00979   // Bouml preserved body begin 0009E3F1
00980   std::stringstream ss;
00981   ss << this->name << ": " << this->value;
00982   value = ss.str();
00983   // Bouml preserved body end 0009E3F1
00984 }
00985 
00986 void InitSineDelay::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00987                                         const YouBotJointStorage& storage) const
00988 {
00989   // Bouml preserved body begin 00083171
00990 
00991   message.stctOutput.commandNumber = msgType;
00992   message.stctOutput.moduleAddress = DRIVE;
00993   message.stctOutput.typeNumber = 244; //InitSineDelay
00994   message.stctOutput.value = (int32)(value.value() * 1000); //sec to µsec
00995 
00996   // Bouml preserved body end 00083171
00997 }
00998 
00999 void InitSineDelay::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01000 {
01001   // Bouml preserved body begin 000831F1
01002   double temp = (int32)message.stctInput.value;
01003   this->value = (temp / 1000.0) * seconds; //µsec to sec
01004   // Bouml preserved body end 000831F1
01005 }
01006 
01007 MassInertiaConstant::MassInertiaConstant()
01008 {
01009   // Bouml preserved body begin 00082771
01010   this->name = "MassInertiaConstant";
01011   this->lowerLimit = INT_MIN;
01012   this->upperLimit = INT_MAX;
01013   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01014   // Bouml preserved body end 00082771
01015 }
01016 
01017 MassInertiaConstant::~MassInertiaConstant()
01018 {
01019   // Bouml preserved body begin 000827F1
01020   // Bouml preserved body end 000827F1
01021 }
01022 
01023 void MassInertiaConstant::getParameter(int& parameter) const
01024 {
01025   // Bouml preserved body begin 00082871
01026   parameter = this->value;
01027   // Bouml preserved body end 00082871
01028 }
01029 
01030 void MassInertiaConstant::setParameter(const int parameter)
01031 {
01032   // Bouml preserved body begin 000828F1
01033   if (this->lowerLimit > parameter)
01034   {
01035     throw std::out_of_range("The parameter exceeds the lower limit");
01036   }
01037   if (this->upperLimit < parameter)
01038   {
01039     throw std::out_of_range("The parameter exceeds the upper limit");
01040   }
01041 
01042   this->value = parameter;
01043   // Bouml preserved body end 000828F1
01044 }
01045 
01046 void MassInertiaConstant::toString(std::string& value)
01047 {
01048   // Bouml preserved body begin 0009E171
01049   std::stringstream ss;
01050   ss << this->name << ": " << this->value;
01051   value = ss.str();
01052   // Bouml preserved body end 0009E171
01053 }
01054 
01055 void MassInertiaConstant::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01056                                               const YouBotJointStorage& storage) const
01057 {
01058   // Bouml preserved body begin 00082971
01059 
01060   message.stctOutput.commandNumber = msgType;
01061   message.stctOutput.moduleAddress = DRIVE;
01062   message.stctOutput.typeNumber = 238; //MassInertiaConstant
01063   message.stctOutput.value = (int32)value; //TODO do convertion
01064 
01065   // Bouml preserved body end 00082971
01066 }
01067 
01068 void MassInertiaConstant::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01069 {
01070   // Bouml preserved body begin 000829F1
01071   this->value = (int32)message.stctInput.value; //TODO do convertion
01072   // Bouml preserved body end 000829F1
01073 }
01074 
01075 MaximumMotorCurrent::MaximumMotorCurrent()
01076 {
01077   // Bouml preserved body begin 0006A5F1
01078   this->name = "MaximumMotorCurrent";
01079   this->lowerLimit = 0 * ampere;
01080   this->upperLimit = INT_MAX * ampere;
01081   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01082   // Bouml preserved body end 0006A5F1
01083 }
01084 
01085 MaximumMotorCurrent::~MaximumMotorCurrent()
01086 {
01087   // Bouml preserved body begin 0006A671
01088   // Bouml preserved body end 0006A671
01089 }
01090 
01091 void MaximumMotorCurrent::getParameter(quantity<current>& parameter) const
01092 {
01093   // Bouml preserved body begin 0006A6F1
01094   parameter = this->value;
01095   // Bouml preserved body end 0006A6F1
01096 }
01097 
01098 void MaximumMotorCurrent::setParameter(const quantity<current>& parameter)
01099 {
01100   // Bouml preserved body begin 0006A771
01101   if (this->lowerLimit > parameter)
01102   {
01103     throw std::out_of_range("The parameter exceeds the lower limit");
01104   }
01105   if (this->upperLimit < parameter)
01106   {
01107     throw std::out_of_range("The parameter exceeds the upper limit");
01108   }
01109 
01110   this->value = parameter;
01111   // Bouml preserved body end 0006A771
01112 }
01113 
01114 void MaximumMotorCurrent::toString(std::string& value)
01115 {
01116   // Bouml preserved body begin 0009CA71
01117   std::stringstream ss;
01118   ss << this->name << ": " << this->value;
01119   value = ss.str();
01120   // Bouml preserved body end 0009CA71
01121 }
01122 
01123 void MaximumMotorCurrent::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01124                                               const YouBotJointStorage& storage) const
01125 {
01126   // Bouml preserved body begin 0006A7F1
01127 
01128   message.stctOutput.commandNumber = msgType;
01129   message.stctOutput.moduleAddress = DRIVE;
01130   message.stctOutput.typeNumber = 6; //MaximumMotorCurrent
01131   message.stctOutput.value = (uint32)(value.value() * 1000.0); // ampere to milli ampere
01132 
01133   // Bouml preserved body end 0006A7F1
01134 }
01135 
01136 void MaximumMotorCurrent::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01137 {
01138   // Bouml preserved body begin 0006A871
01139   double temp = (uint32)message.stctInput.value;
01140   this->value = temp / 1000.0 * ampere; //milli ampere to ampere
01141   // Bouml preserved body end 0006A871
01142 }
01143 
01144 MotorCoilResistance::MotorCoilResistance()
01145 {
01146   // Bouml preserved body begin 00070DF1
01147   this->name = "MotorCoilResistance";
01148   this->lowerLimit = INT_MIN * ohm;
01149   this->upperLimit = INT_MAX * ohm;
01150   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01151   // Bouml preserved body end 00070DF1
01152 }
01153 
01154 MotorCoilResistance::~MotorCoilResistance()
01155 {
01156   // Bouml preserved body begin 00070E71
01157   // Bouml preserved body end 00070E71
01158 }
01159 
01160 void MotorCoilResistance::getParameter(quantity<resistance>& parameter) const
01161 {
01162   // Bouml preserved body begin 00070EF1
01163   parameter = this->value;
01164   // Bouml preserved body end 00070EF1
01165 }
01166 
01167 void MotorCoilResistance::setParameter(const quantity<resistance>& parameter)
01168 {
01169   // Bouml preserved body begin 00093571
01170   if (this->lowerLimit > parameter)
01171   {
01172     throw std::out_of_range("The parameter exceeds the lower limit");
01173   }
01174   if (this->upperLimit < parameter)
01175   {
01176     throw std::out_of_range("The parameter exceeds the upper limit");
01177   }
01178   this->value = parameter;
01179   // Bouml preserved body end 00093571
01180 }
01181 
01182 void MotorCoilResistance::toString(std::string& value)
01183 {
01184   // Bouml preserved body begin 0009E8F1
01185   std::stringstream ss;
01186   ss << this->name << ": " << this->value;
01187   value = ss.str();
01188   // Bouml preserved body end 0009E8F1
01189 }
01190 
01191 void MotorCoilResistance::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01192                                               const YouBotJointStorage& storage) const
01193 {
01194   // Bouml preserved body begin 00070F71
01195   message.stctOutput.commandNumber = msgType;
01196   message.stctOutput.moduleAddress = DRIVE;
01197   message.stctOutput.typeNumber = 240; //MotorCoilResistance
01198   message.stctOutput.value = (int32)(value.value() * 1000); //from ohm to milli ohm
01199   // Bouml preserved body end 00070F71
01200 }
01201 
01202 void MotorCoilResistance::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01203 {
01204   // Bouml preserved body begin 00072271
01205   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
01206   {
01207     double temp = (int32)message.stctInput.value;
01208     this->value = temp / 1000.0 * ohm;
01209   }
01210   // Bouml preserved body end 00072271
01211 }
01212 
01213 MotorControllerTimeout::MotorControllerTimeout()
01214 {
01215   // Bouml preserved body begin 0009F671
01216   this->name = "MotorControllerTimeout";
01217   this->lowerLimit = 0;
01218   this->upperLimit = INT_MAX * seconds;
01219   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01220   // Bouml preserved body end 0009F671
01221 }
01222 
01223 MotorControllerTimeout::~MotorControllerTimeout()
01224 {
01225   // Bouml preserved body begin 0009F6F1
01226   // Bouml preserved body end 0009F6F1
01227 }
01228 
01229 void MotorControllerTimeout::getParameter(quantity<si::time>& parameter) const
01230 {
01231   // Bouml preserved body begin 0009F771
01232   parameter = this->value;
01233   // Bouml preserved body end 0009F771
01234 }
01235 
01236 void MotorControllerTimeout::setParameter(const quantity<si::time>& parameter)
01237 {
01238   // Bouml preserved body begin 0009F7F1
01239   if (this->lowerLimit > parameter)
01240   {
01241     throw std::out_of_range("The parameter exceeds the lower limit");
01242   }
01243   if (this->upperLimit < parameter)
01244   {
01245     throw std::out_of_range("The parameter exceeds the upper limit");
01246   }
01247 
01248   this->value = parameter;
01249   // Bouml preserved body end 0009F7F1
01250 }
01251 
01252 void MotorControllerTimeout::toString(std::string& value)
01253 {
01254   // Bouml preserved body begin 0009F871
01255   std::stringstream ss;
01256   ss << this->name << ": " << this->value;
01257   value = ss.str();
01258   // Bouml preserved body end 0009F871
01259 }
01260 
01261 void MotorControllerTimeout::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01262                                                  const YouBotJointStorage& storage) const
01263 {
01264   // Bouml preserved body begin 0009F8F1
01265 
01266   if (msgType == SAP)
01267   {
01268     message.stctOutput.commandNumber = SGP;
01269   }
01270   else if (msgType == GAP)
01271   {
01272     message.stctOutput.commandNumber = GGP;
01273   }
01274   else
01275   {
01276     message.stctOutput.commandNumber = msgType;
01277   }
01278   message.stctOutput.moduleAddress = DRIVE;
01279   message.stctOutput.typeNumber = 90; //MotorControllerTimeout
01280   message.stctOutput.value = value.value() * 1000; //sec to milli sec
01281 
01282   // Bouml preserved body end 0009F8F1
01283 }
01284 
01285 void MotorControllerTimeout::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01286                                                  const YouBotJointStorage& storage)
01287 {
01288   // Bouml preserved body begin 0009F971
01289   this->value = ((double)message.stctInput.value) / 1000.0 * seconds; //milli sec to sec
01290   // Bouml preserved body end 0009F971
01291 }
01292 
01293 MotorPoles::MotorPoles()
01294 {
01295   // Bouml preserved body begin 000719F1
01296   this->name = "MotorPoles";
01297   this->lowerLimit = 2;
01298   this->upperLimit = 254;
01299   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01300   // Bouml preserved body end 000719F1
01301 }
01302 
01303 MotorPoles::~MotorPoles()
01304 {
01305   // Bouml preserved body begin 00071A71
01306   // Bouml preserved body end 00071A71
01307 }
01308 
01309 void MotorPoles::getParameter(unsigned int& parameter) const
01310 {
01311   // Bouml preserved body begin 00071AF1
01312   parameter = this->value;
01313   // Bouml preserved body end 00071AF1
01314 }
01315 
01316 void MotorPoles::setParameter(const unsigned int parameter)
01317 {
01318   // Bouml preserved body begin 000937F1
01319   if (this->lowerLimit > parameter)
01320   {
01321     throw std::out_of_range("The parameter exceeds the lower limit");
01322   }
01323   if (this->upperLimit < parameter)
01324   {
01325     throw std::out_of_range("The parameter exceeds the upper limit");
01326   }
01327   this->value = parameter;
01328   // Bouml preserved body end 000937F1
01329 }
01330 
01331 void MotorPoles::toString(std::string& value)
01332 {
01333   // Bouml preserved body begin 0009EB71
01334   std::stringstream ss;
01335   ss << this->name << ": " << this->value;
01336   value = ss.str();
01337   // Bouml preserved body end 0009EB71
01338 }
01339 
01340 void MotorPoles::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01341                                      const YouBotJointStorage& storage) const
01342 {
01343   // Bouml preserved body begin 00071B71
01344   message.stctOutput.commandNumber = msgType;
01345   message.stctOutput.moduleAddress = DRIVE;
01346   message.stctOutput.typeNumber = 253; //MotorPoles
01347   message.stctOutput.value = (uint32)value;
01348   // Bouml preserved body end 00071B71
01349 }
01350 
01351 void MotorPoles::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01352 {
01353   // Bouml preserved body begin 00072471
01354   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
01355   {
01356     this->value = (uint32)message.stctInput.value;
01357   }
01358   // Bouml preserved body end 00072471
01359 }
01360 
01361 OperationalTime::OperationalTime()
01362 {
01363   // Bouml preserved body begin 000A03F1
01364   this->name = "OperationalTime";
01365   this->lowerLimit = 0;
01366   this->upperLimit = INT_MAX * seconds;
01367   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01368   // Bouml preserved body end 000A03F1
01369 }
01370 
01371 OperationalTime::~OperationalTime()
01372 {
01373   // Bouml preserved body begin 000A0471
01374   // Bouml preserved body end 000A0471
01375 }
01376 
01377 void OperationalTime::getParameter(quantity<si::time>& parameter) const
01378 {
01379   // Bouml preserved body begin 000A04F1
01380   parameter = this->value;
01381   // Bouml preserved body end 000A04F1
01382 }
01383 
01384 void OperationalTime::setParameter(const quantity<si::time>& parameter)
01385 {
01386   // Bouml preserved body begin 000A0571
01387   if (this->lowerLimit > parameter)
01388   {
01389     throw std::out_of_range("The parameter exceeds the lower limit");
01390   }
01391   if (this->upperLimit < parameter)
01392   {
01393     throw std::out_of_range("The parameter exceeds the upper limit");
01394   }
01395 
01396   this->value = parameter;
01397   // Bouml preserved body end 000A0571
01398 }
01399 
01400 void OperationalTime::toString(std::string& value)
01401 {
01402   // Bouml preserved body begin 000A05F1
01403   std::stringstream ss;
01404   ss << this->name << ": " << this->value;
01405   value = ss.str();
01406   // Bouml preserved body end 000A05F1
01407 }
01408 
01409 void OperationalTime::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01410                                           const YouBotJointStorage& storage) const
01411 {
01412   // Bouml preserved body begin 000A0671
01413   message.stctOutput.commandNumber = msgType;
01414   message.stctOutput.moduleAddress = DRIVE;
01415   message.stctOutput.typeNumber = 30; //OperationalTime
01416   message.stctOutput.value = value.value() / 60.0; //sec to min
01417 
01418   // Bouml preserved body end 000A0671
01419 }
01420 
01421 void OperationalTime::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01422 {
01423   // Bouml preserved body begin 000A06F1
01424   this->value = ((double)message.stctInput.value) * 60.0 * seconds; //min to sec
01425   // Bouml preserved body end 000A06F1
01426 }
01427 
01428 PIDControlTime::PIDControlTime()
01429 {
01430   // Bouml preserved body begin 0006ADF1
01431   this->name = "PIDControlTime";
01432   this->lowerLimit = 0;
01433   this->upperLimit = INT_MAX * seconds;
01434   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01435   // Bouml preserved body end 0006ADF1
01436 }
01437 
01438 PIDControlTime::~PIDControlTime()
01439 {
01440   // Bouml preserved body begin 0006AE71
01441   // Bouml preserved body end 0006AE71
01442 }
01443 
01444 void PIDControlTime::getParameter(quantity<si::time>& parameter) const
01445 {
01446   // Bouml preserved body begin 0006AEF1
01447   parameter = this->value;
01448   // Bouml preserved body end 0006AEF1
01449 }
01450 
01451 void PIDControlTime::setParameter(const quantity<si::time>& parameter)
01452 {
01453   // Bouml preserved body begin 0006AF71
01454   if (this->lowerLimit > parameter)
01455   {
01456     throw std::out_of_range("The parameter exceeds the lower limit");
01457   }
01458   if (this->upperLimit < parameter)
01459   {
01460     throw std::out_of_range("The parameter exceeds the upper limit");
01461   }
01462 
01463   this->value = parameter;
01464   // Bouml preserved body end 0006AF71
01465 }
01466 
01467 void PIDControlTime::toString(std::string& value)
01468 {
01469   // Bouml preserved body begin 0009CF71
01470   std::stringstream ss;
01471   ss << this->name << ": " << this->value;
01472   value = ss.str();
01473   // Bouml preserved body end 0009CF71
01474 }
01475 
01476 void PIDControlTime::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01477                                          const YouBotJointStorage& storage) const
01478 {
01479   // Bouml preserved body begin 0006AFF1
01480 
01481   message.stctOutput.commandNumber = msgType;
01482   message.stctOutput.moduleAddress = DRIVE;
01483   message.stctOutput.typeNumber = 133; //PIDControlTime
01484   message.stctOutput.value = value.value() * 1000; //sec to milli sec
01485 
01486   // Bouml preserved body end 0006AFF1
01487 }
01488 
01489 void PIDControlTime::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01490 {
01491   // Bouml preserved body begin 0006B071
01492   this->value = ((double)message.stctInput.value) / 1000 * seconds; //milli sec to sec
01493   // Bouml preserved body end 0006B071
01494 }
01495 
01496 ReversingEncoderDirection::ReversingEncoderDirection()
01497 {
01498   // Bouml preserved body begin 000716F1
01499   this->name = "ReversingEncoderDirection";
01500   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01501   // Bouml preserved body end 000716F1
01502 }
01503 
01504 ReversingEncoderDirection::~ReversingEncoderDirection()
01505 {
01506   // Bouml preserved body begin 00071771
01507   // Bouml preserved body end 00071771
01508 }
01509 
01510 bool ReversingEncoderDirection::getParameter(bool& parameter) const
01511 {
01512   // Bouml preserved body begin 000717F1
01513   parameter = this->value;
01514   return this->value;
01515   // Bouml preserved body end 000717F1
01516 }
01517 
01518 void ReversingEncoderDirection::setParameter(const bool parameter)
01519 {
01520   // Bouml preserved body begin 000936F1
01521   this->value = parameter;
01522   // Bouml preserved body end 000936F1
01523 }
01524 
01525 void ReversingEncoderDirection::toString(std::string& value)
01526 {
01527   // Bouml preserved body begin 0009EA71
01528   std::stringstream ss;
01529   ss << this->name << ": " << this->value;
01530   value = ss.str();
01531   // Bouml preserved body end 0009EA71
01532 }
01533 
01534 void ReversingEncoderDirection::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01535                                                     const YouBotJointStorage& storage) const
01536 {
01537   // Bouml preserved body begin 00071871
01538   message.stctOutput.commandNumber = msgType;
01539   message.stctOutput.moduleAddress = DRIVE;
01540   message.stctOutput.typeNumber = 251; //ReversingEncoderDirection
01541   message.stctOutput.value = value;
01542   // Bouml preserved body end 00071871
01543 }
01544 
01545 void ReversingEncoderDirection::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01546                                                     const YouBotJointStorage& storage)
01547 {
01548   // Bouml preserved body begin 000723F1
01549   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
01550   {
01551     this->value = message.stctInput.value;
01552   }
01553   // Bouml preserved body end 000723F1
01554 }
01555 
01556 SetEncoderCounterZeroAtNextNChannel::SetEncoderCounterZeroAtNextNChannel()
01557 {
01558   // Bouml preserved body begin 0007C871
01559   this->name = "SetEncoderCounterZeroAtNextNChannel";
01560   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01561   // Bouml preserved body end 0007C871
01562 }
01563 
01564 SetEncoderCounterZeroAtNextNChannel::~SetEncoderCounterZeroAtNextNChannel()
01565 {
01566   // Bouml preserved body begin 0007C8F1
01567   // Bouml preserved body end 0007C8F1
01568 }
01569 
01570 void SetEncoderCounterZeroAtNextNChannel::getParameter(bool& parameter) const
01571 {
01572   // Bouml preserved body begin 0007C971
01573   parameter = this->value;
01574   // Bouml preserved body end 0007C971
01575 }
01576 
01577 void SetEncoderCounterZeroAtNextNChannel::setParameter(const bool parameter)
01578 {
01579   // Bouml preserved body begin 0007C9F1
01580   this->value = parameter;
01581   // Bouml preserved body end 0007C9F1
01582 }
01583 
01584 void SetEncoderCounterZeroAtNextNChannel::toString(std::string& value)
01585 {
01586   // Bouml preserved body begin 0009D571
01587   std::stringstream ss;
01588   ss << this->name << ": " << this->value;
01589   value = ss.str();
01590   // Bouml preserved body end 0009D571
01591 }
01592 
01593 void SetEncoderCounterZeroAtNextNChannel::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01594                                                               const YouBotJointStorage& storage) const
01595 {
01596   // Bouml preserved body begin 0007CA71
01597 
01598   message.stctOutput.commandNumber = msgType;
01599   message.stctOutput.moduleAddress = DRIVE;
01600   message.stctOutput.typeNumber = 161; //SetEncoderCounterZeroAtNextNChannel
01601   message.stctOutput.value = value;
01602 
01603   // Bouml preserved body end 0007CA71
01604 }
01605 
01606 void SetEncoderCounterZeroAtNextNChannel::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01607                                                               const YouBotJointStorage& storage)
01608 {
01609   // Bouml preserved body begin 0007CAF1
01610   this->value = message.stctInput.value;
01611   // Bouml preserved body end 0007CAF1
01612 }
01613 
01614 SetEncoderCounterZeroAtNextSwitch::SetEncoderCounterZeroAtNextSwitch()
01615 {
01616   // Bouml preserved body begin 0007CC71
01617   this->name = "SetEncoderCounterZeroAtNextSwitch";
01618   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01619   // Bouml preserved body end 0007CC71
01620 }
01621 
01622 SetEncoderCounterZeroAtNextSwitch::~SetEncoderCounterZeroAtNextSwitch()
01623 {
01624   // Bouml preserved body begin 0007CCF1
01625   // Bouml preserved body end 0007CCF1
01626 }
01627 
01628 void SetEncoderCounterZeroAtNextSwitch::getParameter(bool& parameter) const
01629 {
01630   // Bouml preserved body begin 0007CD71
01631   parameter = this->value;
01632   // Bouml preserved body end 0007CD71
01633 }
01634 
01635 void SetEncoderCounterZeroAtNextSwitch::setParameter(const bool parameter)
01636 {
01637   // Bouml preserved body begin 0007CDF1
01638   this->value = parameter;
01639   // Bouml preserved body end 0007CDF1
01640 }
01641 
01642 void SetEncoderCounterZeroAtNextSwitch::toString(std::string& value)
01643 {
01644   // Bouml preserved body begin 0009D5F1
01645   std::stringstream ss;
01646   ss << this->name << ": " << this->value;
01647   value = ss.str();
01648   // Bouml preserved body end 0009D5F1
01649 }
01650 
01651 void SetEncoderCounterZeroAtNextSwitch::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01652                                                             const YouBotJointStorage& storage) const
01653 {
01654   // Bouml preserved body begin 0007CE71
01655 
01656   message.stctOutput.commandNumber = msgType;
01657   message.stctOutput.moduleAddress = DRIVE;
01658   message.stctOutput.typeNumber = 162; //SetEncoderCounterZeroAtNextSwitch
01659   message.stctOutput.value = value;
01660 
01661   // Bouml preserved body end 0007CE71
01662 }
01663 
01664 void SetEncoderCounterZeroAtNextSwitch::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01665                                                             const YouBotJointStorage& storage)
01666 {
01667   // Bouml preserved body begin 0007CEF1
01668   this->value = message.stctInput.value;
01669   // Bouml preserved body end 0007CEF1
01670 }
01671 
01672 SetEncoderCounterZeroOnlyOnce::SetEncoderCounterZeroOnlyOnce()
01673 {
01674   // Bouml preserved body begin 0007D071
01675   this->name = "SetEncoderCounterZeroOnlyOnce";
01676   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01677   // Bouml preserved body end 0007D071
01678 }
01679 
01680 SetEncoderCounterZeroOnlyOnce::~SetEncoderCounterZeroOnlyOnce()
01681 {
01682   // Bouml preserved body begin 0007D0F1
01683   // Bouml preserved body end 0007D0F1
01684 }
01685 
01686 void SetEncoderCounterZeroOnlyOnce::getParameter(bool& parameter) const
01687 {
01688   // Bouml preserved body begin 0007D171
01689   parameter = this->value;
01690   // Bouml preserved body end 0007D171
01691 }
01692 
01693 void SetEncoderCounterZeroOnlyOnce::setParameter(const bool parameter)
01694 {
01695   // Bouml preserved body begin 0007D1F1
01696   this->value = parameter;
01697   // Bouml preserved body end 0007D1F1
01698 }
01699 
01700 void SetEncoderCounterZeroOnlyOnce::toString(std::string& value)
01701 {
01702   // Bouml preserved body begin 0009D671
01703   std::stringstream ss;
01704   ss << this->name << ": " << this->value;
01705   value = ss.str();
01706   // Bouml preserved body end 0009D671
01707 }
01708 
01709 void SetEncoderCounterZeroOnlyOnce::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01710                                                         const YouBotJointStorage& storage) const
01711 {
01712   // Bouml preserved body begin 0007D271
01713 
01714   message.stctOutput.commandNumber = msgType;
01715   message.stctOutput.moduleAddress = DRIVE;
01716   message.stctOutput.typeNumber = 163; //SetEncoderCounterZeroOnlyOnce
01717   message.stctOutput.value = value;
01718 
01719   // Bouml preserved body end 0007D271
01720 }
01721 
01722 void SetEncoderCounterZeroOnlyOnce::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01723                                                         const YouBotJointStorage& storage)
01724 {
01725   // Bouml preserved body begin 0007D2F1
01726   this->value = message.stctInput.value;
01727   // Bouml preserved body end 0007D2F1
01728 }
01729 
01730 SineInitializationVelocity::SineInitializationVelocity()
01731 {
01732   // Bouml preserved body begin 0006EDF1
01733   this->name = "SineInitializationVelocity";
01734   this->lowerLimit = INT_MIN;
01735   this->upperLimit = INT_MAX;
01736   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01737   // Bouml preserved body end 0006EDF1
01738 }
01739 
01740 SineInitializationVelocity::~SineInitializationVelocity()
01741 {
01742   // Bouml preserved body begin 0006EE71
01743   // Bouml preserved body end 0006EE71
01744 }
01745 
01746 void SineInitializationVelocity::getParameter(int& parameter) const
01747 {
01748   // Bouml preserved body begin 0006EEF1
01749   parameter = this->value;
01750   // Bouml preserved body end 0006EEF1
01751 }
01752 
01753 void SineInitializationVelocity::setParameter(const int parameter)
01754 {
01755   // Bouml preserved body begin 0006EF71
01756   if (this->lowerLimit > parameter)
01757   {
01758     throw std::out_of_range("The parameter exceeds the lower limit");
01759   }
01760   if (this->upperLimit < parameter)
01761   {
01762     throw std::out_of_range("The parameter exceeds the upper limit");
01763   }
01764 
01765   this->value = parameter;
01766   // Bouml preserved body end 0006EF71
01767 }
01768 
01769 void SineInitializationVelocity::toString(std::string& value)
01770 {
01771   // Bouml preserved body begin 0009E271
01772   std::stringstream ss;
01773   ss << this->name << ": " << this->value;
01774   value = ss.str();
01775   // Bouml preserved body end 0009E271
01776 }
01777 
01778 void SineInitializationVelocity::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01779                                                      const YouBotJointStorage& storage) const
01780 {
01781   // Bouml preserved body begin 0006EFF1
01782 
01783   message.stctOutput.commandNumber = msgType;
01784   message.stctOutput.moduleAddress = DRIVE;
01785   message.stctOutput.typeNumber = 241; //SineInitializationVelocity
01786   message.stctOutput.value = (int32)value;
01787   // Bouml preserved body end 0006EFF1
01788 }
01789 
01790 void SineInitializationVelocity::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01791                                                      const YouBotJointStorage& storage)
01792 {
01793   // Bouml preserved body begin 0006F071
01794   this->value = (int32)message.stctInput.value;
01795   // Bouml preserved body end 0006F071
01796 }
01797 
01798 StopSwitchPolarity::StopSwitchPolarity()
01799 {
01800   // Bouml preserved body begin 0007DC71
01801   this->name = "StopSwitchPolarity";
01802   this->lowerLimit = 0;
01803   this->upperLimit = 3;
01804   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01805   // Bouml preserved body end 0007DC71
01806 }
01807 
01808 StopSwitchPolarity::~StopSwitchPolarity()
01809 {
01810   // Bouml preserved body begin 0007DCF1
01811   // Bouml preserved body end 0007DCF1
01812 }
01813 
01814 void StopSwitchPolarity::getParameter(unsigned int& parameter) const
01815 {
01816   // Bouml preserved body begin 0007DD71
01817   parameter = this->value;
01818   // Bouml preserved body end 0007DD71
01819 }
01820 
01821 void StopSwitchPolarity::setParameter(const unsigned int parameter)
01822 {
01823   // Bouml preserved body begin 0007DDF1
01824   if (this->lowerLimit > parameter)
01825   {
01826     throw std::out_of_range("The parameter exceeds the lower limit");
01827   }
01828   if (this->upperLimit < parameter)
01829   {
01830     throw std::out_of_range("The parameter exceeds the upper limit");
01831   }
01832 
01833   this->value = parameter;
01834   // Bouml preserved body end 0007DDF1
01835 }
01836 
01837 void StopSwitchPolarity::toString(std::string& value)
01838 {
01839   // Bouml preserved body begin 0009D7F1
01840   std::stringstream ss;
01841   ss << this->name << ": " << this->value;
01842   value = ss.str();
01843   // Bouml preserved body end 0009D7F1
01844 }
01845 
01846 void StopSwitchPolarity::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01847                                              const YouBotJointStorage& storage) const
01848 {
01849   // Bouml preserved body begin 0007DE71
01850 
01851   message.stctOutput.commandNumber = msgType;
01852   message.stctOutput.moduleAddress = DRIVE;
01853   message.stctOutput.typeNumber = 166; //StopSwitchPolarity
01854   message.stctOutput.value = value;
01855 
01856   // Bouml preserved body end 0007DE71
01857 }
01858 
01859 void StopSwitchPolarity::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01860 {
01861   // Bouml preserved body begin 0007DEF1
01862   this->value = message.stctInput.value;
01863   // Bouml preserved body end 0007DEF1
01864 }
01865 
01866 ThermalWindingTimeConstant::ThermalWindingTimeConstant()
01867 {
01868   // Bouml preserved body begin 0009FF71
01869   this->name = "ThermalWindingTimeConstant";
01870   this->lowerLimit = 0;
01871   this->upperLimit = INT_MAX * seconds;
01872   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01873   // Bouml preserved body end 0009FF71
01874 }
01875 
01876 ThermalWindingTimeConstant::~ThermalWindingTimeConstant()
01877 {
01878   // Bouml preserved body begin 0009FFF1
01879   // Bouml preserved body end 0009FFF1
01880 }
01881 
01882 void ThermalWindingTimeConstant::getParameter(quantity<si::time>& parameter) const
01883 {
01884   // Bouml preserved body begin 000A0071
01885   parameter = this->value;
01886   // Bouml preserved body end 000A0071
01887 }
01888 
01889 void ThermalWindingTimeConstant::setParameter(const quantity<si::time>& parameter)
01890 {
01891   // Bouml preserved body begin 000A00F1
01892   if (this->lowerLimit > parameter)
01893   {
01894     throw std::out_of_range("The parameter exceeds the lower limit");
01895   }
01896   if (this->upperLimit < parameter)
01897   {
01898     throw std::out_of_range("The parameter exceeds the upper limit");
01899   }
01900 
01901   this->value = parameter;
01902   // Bouml preserved body end 000A00F1
01903 }
01904 
01905 void ThermalWindingTimeConstant::toString(std::string& value)
01906 {
01907   // Bouml preserved body begin 000A0171
01908   std::stringstream ss;
01909   ss << this->name << ": " << this->value;
01910   value = ss.str();
01911   // Bouml preserved body end 000A0171
01912 }
01913 
01914 void ThermalWindingTimeConstant::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01915                                                      const YouBotJointStorage& storage) const
01916 {
01917   // Bouml preserved body begin 000A01F1
01918   message.stctOutput.commandNumber = msgType;
01919   message.stctOutput.moduleAddress = DRIVE;
01920   message.stctOutput.typeNumber = 25; //ThermalWindingTimeConstant
01921   message.stctOutput.value = value.value() * 1000; //sec to milli sec
01922 
01923   // Bouml preserved body end 000A01F1
01924 }
01925 
01926 void ThermalWindingTimeConstant::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01927                                                      const YouBotJointStorage& storage)
01928 {
01929   // Bouml preserved body begin 000A0271
01930   this->value = ((double)message.stctInput.value) / 1000.0 * seconds; //milli sec to sec
01931   // Bouml preserved body end 000A0271
01932 }
01933 
01934 MotorHaltedVelocity::MotorHaltedVelocity()
01935 {
01936   // Bouml preserved body begin 000CB871
01937   this->name = "MotorHaltedVelocity";
01938   this->lowerLimit = INT_MIN;
01939   this->upperLimit = INT_MAX;
01940   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01941   // Bouml preserved body end 000CB871
01942 }
01943 
01944 MotorHaltedVelocity::~MotorHaltedVelocity()
01945 {
01946   // Bouml preserved body begin 000CB8F1
01947   // Bouml preserved body end 000CB8F1
01948 }
01949 
01950 void MotorHaltedVelocity::getParameter(int& parameter) const
01951 {
01952   // Bouml preserved body begin 000CB971
01953   parameter = this->value;
01954   // Bouml preserved body end 000CB971
01955 }
01956 
01957 void MotorHaltedVelocity::setParameter(const int parameter)
01958 {
01959   // Bouml preserved body begin 000CB9F1
01960   if (this->lowerLimit > parameter)
01961   {
01962     throw std::out_of_range("The parameter exceeds the lower limit");
01963   }
01964   if (this->upperLimit < parameter)
01965   {
01966     throw std::out_of_range("The parameter exceeds the upper limit");
01967   }
01968 
01969   this->value = parameter;
01970   // Bouml preserved body end 000CB9F1
01971 }
01972 
01973 void MotorHaltedVelocity::toString(std::string& value)
01974 {
01975   // Bouml preserved body begin 000CBA71
01976   std::stringstream ss;
01977   ss << this->name << ": " << this->value;
01978   value = ss.str();
01979   // Bouml preserved body end 000CBA71
01980 }
01981 
01982 void MotorHaltedVelocity::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01983                                               const YouBotJointStorage& storage) const
01984 {
01985   // Bouml preserved body begin 000CBAF1
01986 
01987   message.stctOutput.commandNumber = msgType;
01988   message.stctOutput.moduleAddress = DRIVE;
01989   message.stctOutput.typeNumber = 9; //MotorHaltedVelocity
01990   message.stctOutput.value = (int32)value;
01991   // Bouml preserved body end 000CBAF1
01992 }
01993 
01994 void MotorHaltedVelocity::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
01995 {
01996   // Bouml preserved body begin 000CBB71
01997   this->value = (int32)message.stctInput.value;
01998   // Bouml preserved body end 000CBB71
01999 }
02000 
02001 } // namespace youbot


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Oct 6 2014 09:08:02