YouBotJointParameter.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/YouBotJointParameter.hpp>
00052 namespace youbot
00053 {
00054 
00055 YouBotApiJointParameter::YouBotApiJointParameter()
00056 {
00057   // Bouml preserved body begin 000D91F1
00058   // Bouml preserved body end 000D91F1
00059 }
00060 
00061 YouBotApiJointParameter::~YouBotApiJointParameter()
00062 {
00063   // Bouml preserved body begin 000D9271
00064   // Bouml preserved body end 000D9271
00065 }
00066 
00067 YouBotJointParameter::YouBotJointParameter()
00068 {
00069   // Bouml preserved body begin 0005BB71
00070   // Bouml preserved body end 0005BB71
00071 }
00072 
00073 YouBotJointParameter::~YouBotJointParameter()
00074 {
00075   // Bouml preserved body begin 0005BBF1
00076   // Bouml preserved body end 0005BBF1
00077 }
00078 
00079 JointName::JointName()
00080 {
00081   // Bouml preserved body begin 0005C0F1
00082   this->name = "JointName";
00083   this->parameterType = API_PARAMETER;
00084   // Bouml preserved body end 0005C0F1
00085 }
00086 
00087 JointName::~JointName()
00088 {
00089   // Bouml preserved body begin 0005C171
00090   // Bouml preserved body end 0005C171
00091 }
00092 
00093 void JointName::getParameter(std::string& parameter) const
00094 {
00095   // Bouml preserved body begin 0005C1F1
00096   parameter = this->value;
00097   // Bouml preserved body end 0005C1F1
00098 }
00099 
00100 void JointName::setParameter(const std::string parameter)
00101 {
00102   // Bouml preserved body begin 0005C271
00103   this->value = parameter;
00104   // Bouml preserved body end 0005C271
00105 }
00106 
00107 void JointName::toString(std::string& value)
00108 {
00109   // Bouml preserved body begin 0009C471
00110   std::stringstream ss;
00111   ss << this->name << ": " << this->value;
00112   value = ss.str();
00113   // Bouml preserved body end 0009C471
00114 }
00115 
00116 InitializeJoint::InitializeJoint()
00117 {
00118   // Bouml preserved body begin 00095171
00119   this->name = "InitializeJoint";
00120   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00121   // Bouml preserved body end 00095171
00122 }
00123 
00124 InitializeJoint::~InitializeJoint()
00125 {
00126   // Bouml preserved body begin 000951F1
00127   // Bouml preserved body end 000951F1
00128 }
00129 
00130 void InitializeJoint::getParameter(bool& parameter) const
00131 {
00132   // Bouml preserved body begin 00095271
00133   parameter = this->value;
00134   // Bouml preserved body end 00095271
00135 }
00136 
00137 void InitializeJoint::setParameter(const bool parameter)
00138 {
00139   // Bouml preserved body begin 000952F1
00140   this->value = parameter;
00141   // Bouml preserved body end 000952F1
00142 }
00143 
00144 void InitializeJoint::toString(std::string& value)
00145 {
00146   // Bouml preserved body begin 0009C971
00147   std::stringstream ss;
00148   ss << this->name << ": " << this->value;
00149   value = ss.str();
00150   // Bouml preserved body end 0009C971
00151 }
00152 
00153 void InitializeJoint::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00154                                           const YouBotJointStorage& storage) const
00155 {
00156   // Bouml preserved body begin 00095371
00157   message.stctOutput.commandNumber = msgType;
00158   message.stctOutput.moduleAddress = DRIVE;
00159   message.stctOutput.typeNumber = 15; //InitializeJoint
00160   message.stctOutput.value = (int)this->value;
00161   // Bouml preserved body end 00095371
00162 }
00163 
00164 void InitializeJoint::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00165 {
00166   // Bouml preserved body begin 000953F1
00167   this->value = message.stctInput.value;
00168   // Bouml preserved body end 000953F1
00169 }
00170 
00171 CalibrateJoint::CalibrateJoint()
00172 {
00173   // Bouml preserved body begin 00061F71
00174   this->name = "CalibrateJoint";
00175   this->parameterType = API_PARAMETER;
00176   // Bouml preserved body end 00061F71
00177 }
00178 
00179 CalibrateJoint::~CalibrateJoint()
00180 {
00181   // Bouml preserved body begin 00061FF1
00182   // Bouml preserved body end 00061FF1
00183 }
00184 
00185 void CalibrateJoint::getParameter(bool& doCalibration, CalibrationDirection& calibrationDirection,
00186                                   quantity<si::current>& maxCurrent) const
00187 {
00188   // Bouml preserved body begin 00062071
00189   doCalibration = this->doCalibration;
00190   calibrationDirection = this->calibrationDirection;
00191   maxCurrent = this->maxCurrent;
00192   // Bouml preserved body end 00062071
00193 }
00194 
00195 void CalibrateJoint::setParameter(const bool doCalibration, CalibrationDirection calibrationDirection,
00196                                   const quantity<si::current>& maxCurrent)
00197 {
00198   // Bouml preserved body begin 000620F1
00199   this->doCalibration = doCalibration;
00200   this->calibrationDirection = calibrationDirection;
00201   this->maxCurrent = maxCurrent;
00202   // Bouml preserved body end 000620F1
00203 }
00204 
00205 void CalibrateJoint::toString(std::string& value)
00206 {
00207   // Bouml preserved body begin 0009C771
00208   std::stringstream ss;
00209   ss << this->name << ": " << "doCalibration " << this->doCalibration << " calibrationDirection "
00210       << this->calibrationDirection << " maxCurrent " << this->maxCurrent;
00211   value = ss.str();
00212   // Bouml preserved body end 0009C771
00213 }
00214 
00215 FirmwareVersion::FirmwareVersion()
00216 {
00217   // Bouml preserved body begin 00098D71
00218   this->name = "FirmwareVersion";
00219   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00220   // Bouml preserved body end 00098D71
00221 }
00222 
00223 FirmwareVersion::~FirmwareVersion()
00224 {
00225   // Bouml preserved body begin 00098DF1
00226   // Bouml preserved body end 00098DF1
00227 }
00228 
00229 void FirmwareVersion::getParameter(int& controllerType, std::string& firmwareVersion) const
00230 {
00231   // Bouml preserved body begin 00098E71
00232   controllerType = this->controllerType;
00233   firmwareVersion = this->firmwareVersion;
00234   // Bouml preserved body end 00098E71
00235 }
00236 
00237 void FirmwareVersion::setParameter(const int controllerType, const std::string firmwareVersion)
00238 {
00239   // Bouml preserved body begin 00098EF1
00240   this->controllerType = controllerType;
00241   this->firmwareVersion = firmwareVersion;
00242   // Bouml preserved body end 00098EF1
00243 }
00244 
00245 void FirmwareVersion::toString(std::string& value)
00246 {
00247   // Bouml preserved body begin 0009C571
00248   std::stringstream ss;
00249   ss << this->name << ": Controller: " << this->controllerType << " Version: " << this->firmwareVersion;
00250   value = ss.str();
00251   // Bouml preserved body end 0009C571
00252 }
00253 
00254 void FirmwareVersion::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00255                                           const YouBotJointStorage& storage) const
00256 {
00257   // Bouml preserved body begin 00098F71
00258   message.stctOutput.commandNumber = FIRMWARE_VERSION;
00259   message.stctOutput.moduleAddress = DRIVE;
00260   message.stctOutput.typeNumber = 0; //FirmwareVersion
00261   message.stctOutput.value = 0;
00262   // Bouml preserved body end 00098F71
00263 }
00264 
00265 void FirmwareVersion::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00266 {
00267   // Bouml preserved body begin 00098FF1
00268   // Bouml preserved body end 00098FF1
00269 }
00270 
00271 GearRatio::GearRatio()
00272 {
00273   // Bouml preserved body begin 0005BDF1
00274   this->name = "GearRatio";
00275   this->parameterType = API_PARAMETER;
00276   // Bouml preserved body end 0005BDF1
00277 }
00278 
00279 GearRatio::~GearRatio()
00280 {
00281   // Bouml preserved body begin 0005BE71
00282   // Bouml preserved body end 0005BE71
00283 }
00284 
00285 void GearRatio::getParameter(double& parameter) const
00286 {
00287   // Bouml preserved body begin 0005BEF1
00288   parameter = this->value;
00289   // Bouml preserved body end 0005BEF1
00290 }
00291 
00292 void GearRatio::setParameter(const double parameter)
00293 {
00294   // Bouml preserved body begin 0005BF71
00295   if (parameter == 0)
00296   {
00297     throw std::out_of_range("A Gear Ratio of 0 is not allowed");
00298   }
00299   this->value = parameter;
00300   // Bouml preserved body end 0005BF71
00301 }
00302 
00303 void GearRatio::toString(std::string& value)
00304 {
00305   // Bouml preserved body begin 0009C5F1
00306   std::stringstream ss;
00307   ss << this->name << ": " << this->value;
00308   value = ss.str();
00309   // Bouml preserved body end 0009C5F1
00310 }
00311 
00312 EncoderTicksPerRound::EncoderTicksPerRound()
00313 {
00314   // Bouml preserved body begin 0005C3F1
00315   this->name = "EncoderTicksPerRound";
00316   this->parameterType = API_PARAMETER;
00317   // Bouml preserved body end 0005C3F1
00318 }
00319 
00320 EncoderTicksPerRound::~EncoderTicksPerRound()
00321 {
00322   // Bouml preserved body begin 0005C471
00323   // Bouml preserved body end 0005C471
00324 }
00325 
00326 void EncoderTicksPerRound::getParameter(unsigned int& parameter) const
00327 {
00328   // Bouml preserved body begin 0005C4F1
00329   parameter = this->value;
00330   // Bouml preserved body end 0005C4F1
00331 }
00332 
00333 void EncoderTicksPerRound::setParameter(const unsigned int parameter)
00334 {
00335   // Bouml preserved body begin 0005C571
00336   if (parameter == 0)
00337   {
00338     throw std::out_of_range("Zero Encoder Ticks per Round are not allowed");
00339   }
00340   this->value = parameter;
00341   // Bouml preserved body end 0005C571
00342 }
00343 
00344 void EncoderTicksPerRound::toString(std::string& value)
00345 {
00346   // Bouml preserved body begin 0009C671
00347   std::stringstream ss;
00348   ss << this->name << ": " << this->value;
00349   value = ss.str();
00350   // Bouml preserved body end 0009C671
00351 }
00352 
00353 InverseMovementDirection::InverseMovementDirection()
00354 {
00355   // Bouml preserved body begin 0005C6F1
00356   this->name = "InverseMovementDirection";
00357   this->parameterType = API_PARAMETER;
00358   // Bouml preserved body end 0005C6F1
00359 }
00360 
00361 InverseMovementDirection::~InverseMovementDirection()
00362 {
00363   // Bouml preserved body begin 0005C771
00364   // Bouml preserved body end 0005C771
00365 }
00366 
00367 void InverseMovementDirection::getParameter(bool& parameter) const
00368 {
00369   // Bouml preserved body begin 0005C7F1
00370   parameter = this->value;
00371   // Bouml preserved body end 0005C7F1
00372 }
00373 
00374 void InverseMovementDirection::setParameter(const bool parameter)
00375 {
00376   // Bouml preserved body begin 0005C871
00377   this->value = parameter;
00378   // Bouml preserved body end 0005C871
00379 }
00380 
00381 void InverseMovementDirection::toString(std::string& value)
00382 {
00383   // Bouml preserved body begin 0009C6F1
00384   std::stringstream ss;
00385   ss << this->name << ": " << this->value;
00386   value = ss.str();
00387   // Bouml preserved body end 0009C6F1
00388 }
00389 
00390 JointLimits::JointLimits()
00391 {
00392   // Bouml preserved body begin 00063EF1
00393   this->name = "JointLimits";
00394   this->parameterType = API_PARAMETER;
00395   this->lowerLimit = 0;
00396   this->upperLimit = 0;
00397   this->areLimitsActive = true;
00398   // Bouml preserved body end 00063EF1
00399 }
00400 
00401 JointLimits::~JointLimits()
00402 {
00403   // Bouml preserved body begin 00063F71
00404   // Bouml preserved body end 00063F71
00405 }
00406 
00407 void JointLimits::getParameter(int& lowerLimit, int& upperLimit, bool& areLimitsActive) const
00408 {
00409   // Bouml preserved body begin 00063FF1
00410   lowerLimit = this->lowerLimit;
00411   upperLimit = this->upperLimit;
00412   areLimitsActive = this->areLimitsActive;
00413   // Bouml preserved body end 00063FF1
00414 }
00415 
00416 void JointLimits::setParameter(const int lowerLimit, const int upperLimit, const bool activateLimits)
00417 {
00418   // Bouml preserved body begin 00064071
00419   if (lowerLimit > upperLimit)
00420   {
00421     throw std::out_of_range("The lower joint limit it not allowed to be bigger than the upper limit");
00422   }
00423   this->lowerLimit = lowerLimit;
00424   this->upperLimit = upperLimit;
00425   this->areLimitsActive = activateLimits;
00426   // Bouml preserved body end 00064071
00427 }
00428 
00429 void JointLimits::toString(std::string& value)
00430 {
00431   // Bouml preserved body begin 0009C7F1
00432   std::stringstream ss;
00433   ss << this->name << ": lower Limit: " << this->lowerLimit << " upper Limit: " << this->upperLimit;
00434   value = ss.str();
00435   // Bouml preserved body end 0009C7F1
00436 }
00437 
00438 JointLimitsRadian::JointLimitsRadian()
00439 {
00440   // Bouml preserved body begin 000D3EF1
00441   this->name = "JointLimitsRadian";
00442   this->parameterType = API_PARAMETER;
00443   this->lowerLimit = 0;
00444   this->upperLimit = 0;
00445   this->areLimitsActive = true;
00446   // Bouml preserved body end 000D3EF1
00447 }
00448 
00449 JointLimitsRadian::~JointLimitsRadian()
00450 {
00451   // Bouml preserved body begin 000D3F71
00452   // Bouml preserved body end 000D3F71
00453 }
00454 
00455 void JointLimitsRadian::getParameter(quantity<plane_angle>& lowerLimit, quantity<plane_angle>& upperLimit,
00456                                      bool& areLimitsActive) const
00457 {
00458   // Bouml preserved body begin 000D3FF1
00459   lowerLimit = this->lowerLimit;
00460   upperLimit = this->upperLimit;
00461   areLimitsActive = this->areLimitsActive;
00462   // Bouml preserved body end 000D3FF1
00463 }
00464 
00465 void JointLimitsRadian::setParameter(const quantity<plane_angle>& lowerLimit, const quantity<plane_angle>& upperLimit,
00466                                      const bool activateLimits)
00467 {
00468   // Bouml preserved body begin 000D4071
00469   if (lowerLimit > upperLimit)
00470   {
00471     throw std::out_of_range("The lower joint limit it not allowed to be bigger than the upper limit");
00472   }
00473   this->lowerLimit = lowerLimit;
00474   this->upperLimit = upperLimit;
00475   this->areLimitsActive = activateLimits;
00476   // Bouml preserved body end 000D4071
00477 }
00478 
00479 void JointLimitsRadian::toString(std::string& value)
00480 {
00481   // Bouml preserved body begin 000D40F1
00482   std::stringstream ss;
00483   ss << this->name << ": lower Limit: " << this->lowerLimit << " upper Limit: " << this->upperLimit;
00484   value = ss.str();
00485   // Bouml preserved body end 000D40F1
00486 }
00487 
00488 TorqueConstant::TorqueConstant()
00489 {
00490   // Bouml preserved body begin 000C71F1
00491   this->name = "TorqueConstant";
00492   this->parameterType = API_PARAMETER;
00493   // Bouml preserved body end 000C71F1
00494 }
00495 
00496 TorqueConstant::~TorqueConstant()
00497 {
00498   // Bouml preserved body begin 000C7271
00499   // Bouml preserved body end 000C7271
00500 }
00501 
00502 void TorqueConstant::getParameter(double& parameter) const
00503 {
00504   // Bouml preserved body begin 000C72F1
00505   parameter = this->value;
00506   // Bouml preserved body end 000C72F1
00507 }
00508 
00509 void TorqueConstant::setParameter(const double parameter)
00510 {
00511   // Bouml preserved body begin 000C7371
00512   if (parameter == 0 || parameter < 0)
00513   {
00514     throw std::out_of_range("It is not allowed to set a zero or negative torque constant");
00515   }
00516   this->value = parameter;
00517   // Bouml preserved body end 000C7371
00518 }
00519 
00520 void TorqueConstant::toString(std::string& value)
00521 {
00522   // Bouml preserved body begin 000C73F1
00523   std::stringstream ss;
00524   ss << this->name << ": " << this->value;
00525   value = ss.str();
00526   // Bouml preserved body end 000C73F1
00527 }
00528 
00529 MaximumPositioningVelocity::MaximumPositioningVelocity()
00530 {
00531   // Bouml preserved body begin 0005A171
00532   this->name = "MaximumPositioningVelocity";
00533   this->lowerLimit = INT_MIN * radian_per_second;
00534   this->upperLimit = INT_MAX * radian_per_second;
00535   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00536   // Bouml preserved body end 0005A171
00537 }
00538 
00539 MaximumPositioningVelocity::~MaximumPositioningVelocity()
00540 {
00541   // Bouml preserved body begin 0005A1F1
00542   // Bouml preserved body end 0005A1F1
00543 }
00544 
00545 void MaximumPositioningVelocity::getParameter(quantity<angular_velocity>& parameter) const
00546 {
00547   // Bouml preserved body begin 00059CF1
00548   parameter = this->value;
00549   // Bouml preserved body end 00059CF1
00550 }
00551 
00552 void MaximumPositioningVelocity::setParameter(const quantity<angular_velocity>& parameter)
00553 {
00554   // Bouml preserved body begin 00059C71
00555   if (this->lowerLimit > parameter)
00556   {
00557     throw std::out_of_range("The parameter exceeds the lower limit");
00558   }
00559   if (this->upperLimit < parameter)
00560   {
00561     throw std::out_of_range("The parameter exceeds the upper limit");
00562   }
00563 
00564   this->value = parameter;
00565   // Bouml preserved body end 00059C71
00566 }
00567 
00568 void MaximumPositioningVelocity::toString(std::string& value)
00569 {
00570   // Bouml preserved body begin 0009C4F1
00571   std::stringstream ss;
00572   ss << this->name << ": " << this->value;
00573   value = ss.str();
00574   // Bouml preserved body end 0009C4F1
00575 }
00576 
00577 void MaximumPositioningVelocity::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00578                                                      const YouBotJointStorage& storage) const
00579 {
00580   // Bouml preserved body begin 0005A0F1
00581 
00582   message.stctOutput.commandNumber = msgType;
00583   message.stctOutput.moduleAddress = DRIVE;
00584   message.stctOutput.typeNumber = 4; //MaximumPositioningVelocity
00585   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
00586 
00587   // Bouml preserved body end 0005A0F1
00588 }
00589 
00590 void MaximumPositioningVelocity::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00591                                                      const YouBotJointStorage& storage)
00592 {
00593   // Bouml preserved body begin 0005A071
00594   double motorRPM = (int32)message.stctInput.value;
00595   this->value = ((motorRPM / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00596   // Bouml preserved body end 0005A071
00597 }
00598 
00599 MotorAcceleration::MotorAcceleration()
00600 {
00601   // Bouml preserved body begin 0006A9F1
00602   this->name = "MotorAcceleration";
00603   this->lowerLimit = INT_MIN * radian_per_second / second;
00604   this->upperLimit = INT_MAX * radian_per_second / second;
00605   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00606   // Bouml preserved body end 0006A9F1
00607 }
00608 
00609 MotorAcceleration::~MotorAcceleration()
00610 {
00611   // Bouml preserved body begin 0006AA71
00612   // Bouml preserved body end 0006AA71
00613 }
00614 
00615 void MotorAcceleration::getParameter(quantity<angular_acceleration>& parameter) const
00616 {
00617   // Bouml preserved body begin 0006AAF1
00618   parameter = this->value;
00619   // Bouml preserved body end 0006AAF1
00620 }
00621 
00622 void MotorAcceleration::setParameter(const quantity<angular_acceleration>& parameter)
00623 {
00624   // Bouml preserved body begin 0006AB71
00625   if (this->lowerLimit > parameter)
00626   {
00627     throw std::out_of_range("The parameter exceeds the lower limit");
00628   }
00629   if (this->upperLimit < parameter)
00630   {
00631     throw std::out_of_range("The parameter exceeds the upper limit");
00632   }
00633 
00634   this->value = parameter;
00635   // Bouml preserved body end 0006AB71
00636 }
00637 
00638 void MotorAcceleration::toString(std::string& value)
00639 {
00640   // Bouml preserved body begin 0009CCF1
00641   std::stringstream ss;
00642   ss << this->name << ": " << this->value;
00643   value = ss.str();
00644   // Bouml preserved body end 0009CCF1
00645 }
00646 
00647 void MotorAcceleration::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00648                                             const YouBotJointStorage& storage) const
00649 {
00650   // Bouml preserved body begin 0006ABF1
00651 
00652   message.stctOutput.commandNumber = msgType;
00653   message.stctOutput.moduleAddress = DRIVE;
00654   message.stctOutput.typeNumber = 11; //MotorAcceleration
00655   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
00656 
00657   // Bouml preserved body end 0006ABF1
00658 }
00659 
00660 void MotorAcceleration::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00661 {
00662   // Bouml preserved body begin 0006AC71
00663   double motorRPMperSec = (int32)message.stctInput.value;
00664   this->value = ((motorRPMperSec / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second / second;
00665   // Bouml preserved body end 0006AC71
00666 }
00667 
00668 RampGeneratorSpeedAndPositionControl::RampGeneratorSpeedAndPositionControl()
00669 {
00670   // Bouml preserved body begin 0006C5F1
00671   this->name = "RampGeneratorSpeedAndPositionControl";
00672   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00673   // Bouml preserved body end 0006C5F1
00674 }
00675 
00676 RampGeneratorSpeedAndPositionControl::~RampGeneratorSpeedAndPositionControl()
00677 {
00678   // Bouml preserved body begin 0006C671
00679   // Bouml preserved body end 0006C671
00680 }
00681 
00682 void RampGeneratorSpeedAndPositionControl::getParameter(bool& parameter) const
00683 {
00684   // Bouml preserved body begin 0006C6F1
00685   parameter = this->value;
00686   // Bouml preserved body end 0006C6F1
00687 }
00688 
00689 void RampGeneratorSpeedAndPositionControl::setParameter(const bool parameter)
00690 {
00691   // Bouml preserved body begin 0006C771
00692   this->value = parameter;
00693   // Bouml preserved body end 0006C771
00694 }
00695 
00696 void RampGeneratorSpeedAndPositionControl::toString(std::string& value)
00697 {
00698   // Bouml preserved body begin 0009D471
00699   std::stringstream ss;
00700   ss << this->name << ": " << this->value;
00701   value = ss.str();
00702   // Bouml preserved body end 0009D471
00703 }
00704 
00705 void RampGeneratorSpeedAndPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
00706                                                                TMCLCommandNumber msgType,
00707                                                                const YouBotJointStorage& storage) const
00708 {
00709   // Bouml preserved body begin 0006C7F1
00710 
00711   message.stctOutput.commandNumber = msgType;
00712   message.stctOutput.moduleAddress = DRIVE;
00713   message.stctOutput.typeNumber = 146; //RampGeneratorSpeedAndPositionControl
00714   message.stctOutput.value = value;
00715 
00716   // Bouml preserved body end 0006C7F1
00717 }
00718 
00719 void RampGeneratorSpeedAndPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00720                                                                const YouBotJointStorage& storage)
00721 {
00722   // Bouml preserved body begin 0006C871
00723   this->value = message.stctInput.value;
00724   // Bouml preserved body end 0006C871
00725 }
00726 
00727 PositionControlSwitchingThreshold::PositionControlSwitchingThreshold()
00728 {
00729   // Bouml preserved body begin 0006F9F1
00730   this->name = "PositionControlSwitchingThreshold";
00731   this->lowerLimit = INT_MIN * radian_per_second;
00732   this->upperLimit = INT_MAX * radian_per_second;
00733   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00734   // Bouml preserved body end 0006F9F1
00735 }
00736 
00737 PositionControlSwitchingThreshold::~PositionControlSwitchingThreshold()
00738 {
00739   // Bouml preserved body begin 0006FA71
00740   // Bouml preserved body end 0006FA71
00741 }
00742 
00743 void PositionControlSwitchingThreshold::getParameter(quantity<angular_velocity>& parameter) const
00744 {
00745   // Bouml preserved body begin 0006FAF1
00746   parameter = this->value;
00747   // Bouml preserved body end 0006FAF1
00748 }
00749 
00750 void PositionControlSwitchingThreshold::setParameter(const quantity<angular_velocity>& parameter)
00751 {
00752   // Bouml preserved body begin 0006FB71
00753   if (this->lowerLimit > parameter)
00754   {
00755     throw std::out_of_range("The parameter exceeds the lower limit");
00756   }
00757   if (this->upperLimit < parameter)
00758   {
00759     throw std::out_of_range("The parameter exceeds the upper limit");
00760   }
00761 
00762   this->value = parameter;
00763   // Bouml preserved body end 0006FB71
00764 }
00765 
00766 void PositionControlSwitchingThreshold::toString(std::string& value)
00767 {
00768   // Bouml preserved body begin 0009CD71
00769   std::stringstream ss;
00770   ss << this->name << ": " << this->value;
00771   value = ss.str();
00772   // Bouml preserved body end 0009CD71
00773 }
00774 
00775 void PositionControlSwitchingThreshold::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00776                                                             const YouBotJointStorage& storage) const
00777 {
00778   // Bouml preserved body begin 0006FBF1
00779 
00780   message.stctOutput.commandNumber = msgType;
00781   message.stctOutput.moduleAddress = DRIVE;
00782   message.stctOutput.typeNumber = 12; //PositionControlSwitchingThreshold
00783   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
00784 
00785   // Bouml preserved body end 0006FBF1
00786 }
00787 
00788 void PositionControlSwitchingThreshold::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00789                                                             const YouBotJointStorage& storage)
00790 {
00791   // Bouml preserved body begin 0006FC71
00792   double motorRPM = (int32)message.stctInput.value;
00793   this->value = ((motorRPM / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00794   // Bouml preserved body end 0006FC71
00795 }
00796 
00797 SpeedControlSwitchingThreshold::SpeedControlSwitchingThreshold()
00798 {
00799   // Bouml preserved body begin 0006A1F1
00800   this->name = "SpeedControlSwitchingThreshold";
00801   this->lowerLimit = INT_MIN * radian_per_second;
00802   this->upperLimit = INT_MAX * radian_per_second;
00803   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00804   // Bouml preserved body end 0006A1F1
00805 }
00806 
00807 SpeedControlSwitchingThreshold::~SpeedControlSwitchingThreshold()
00808 {
00809   // Bouml preserved body begin 0006A271
00810   // Bouml preserved body end 0006A271
00811 }
00812 
00813 void SpeedControlSwitchingThreshold::getParameter(quantity<angular_velocity>& parameter) const
00814 {
00815   // Bouml preserved body begin 0006A2F1
00816   parameter = this->value;
00817   // Bouml preserved body end 0006A2F1
00818 }
00819 
00820 void SpeedControlSwitchingThreshold::setParameter(const quantity<angular_velocity>& parameter)
00821 {
00822   // Bouml preserved body begin 0006A371
00823   if (this->lowerLimit > parameter)
00824   {
00825     throw std::out_of_range("The parameter exceeds the lower limit");
00826   }
00827   if (this->upperLimit < parameter)
00828   {
00829     throw std::out_of_range("The parameter exceeds the upper limit");
00830   }
00831 
00832   this->value = parameter;
00833   // Bouml preserved body end 0006A371
00834 }
00835 
00836 void SpeedControlSwitchingThreshold::toString(std::string& value)
00837 {
00838   // Bouml preserved body begin 0009CB71
00839   std::stringstream ss;
00840   ss << this->name << ": " << this->value;
00841   value = ss.str();
00842   // Bouml preserved body end 0009CB71
00843 }
00844 
00845 void SpeedControlSwitchingThreshold::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00846                                                          const YouBotJointStorage& storage) const
00847 {
00848   // Bouml preserved body begin 0006A3F1
00849 
00850   message.stctOutput.commandNumber = msgType;
00851   message.stctOutput.moduleAddress = DRIVE;
00852   message.stctOutput.typeNumber = 8; //SpeedControlSwitchingThreshold
00853   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
00854 
00855   // Bouml preserved body end 0006A3F1
00856 }
00857 
00858 void SpeedControlSwitchingThreshold::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00859                                                          const YouBotJointStorage& storage)
00860 {
00861   // Bouml preserved body begin 0006A471
00862   double motorRPM = (int32)message.stctInput.value;
00863   this->value = ((motorRPM / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00864   // Bouml preserved body end 0006A471
00865 }
00866 
00867 VelocityThresholdForHallFX::VelocityThresholdForHallFX()
00868 {
00869   // Bouml preserved body begin 00107FF1
00870   this->name = "VelocityThresholdForHallFX";
00871   this->lowerLimit = INT_MIN * radian_per_second;
00872   this->upperLimit = INT_MAX * radian_per_second;
00873   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00874   // Bouml preserved body end 00107FF1
00875 }
00876 
00877 VelocityThresholdForHallFX::~VelocityThresholdForHallFX()
00878 {
00879   // Bouml preserved body begin 00108071
00880   // Bouml preserved body end 00108071
00881 }
00882 
00883 void VelocityThresholdForHallFX::getParameter(quantity<angular_velocity>& parameter) const
00884 {
00885   // Bouml preserved body begin 001080F1
00886   parameter = this->value;
00887   // Bouml preserved body end 001080F1
00888 }
00889 
00890 void VelocityThresholdForHallFX::setParameter(const quantity<angular_velocity>& parameter)
00891 {
00892   // Bouml preserved body begin 00108171
00893   if (this->lowerLimit > parameter)
00894   {
00895     throw std::out_of_range("The parameter exceeds the lower limit");
00896   }
00897   if (this->upperLimit < parameter)
00898   {
00899     throw std::out_of_range("The parameter exceeds the upper limit");
00900   }
00901 
00902   this->value = parameter;
00903   // Bouml preserved body end 00108171
00904 }
00905 
00906 void VelocityThresholdForHallFX::toString(std::string& value)
00907 {
00908   // Bouml preserved body begin 001081F1
00909   std::stringstream ss;
00910   ss << this->name << ": " << this->value;
00911   value = ss.str();
00912   // Bouml preserved body end 001081F1
00913 }
00914 
00915 void VelocityThresholdForHallFX::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00916                                                      const YouBotJointStorage& storage) const
00917 {
00918   // Bouml preserved body begin 00108271
00919 
00920   message.stctOutput.commandNumber = msgType;
00921   message.stctOutput.moduleAddress = DRIVE;
00922   message.stctOutput.typeNumber = 14; //VelocityThresholdForHallFX
00923   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
00924 
00925   // Bouml preserved body end 00108271
00926 }
00927 
00928 void VelocityThresholdForHallFX::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00929                                                      const YouBotJointStorage& storage)
00930 {
00931   // Bouml preserved body begin 001082F1
00932   double motorRPM = (int32)message.stctInput.value;
00933   this->value = ((motorRPM / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00934   // Bouml preserved body end 001082F1
00935 }
00936 
00937 PParameterFirstParametersPositionControl::PParameterFirstParametersPositionControl()
00938 {
00939   // Bouml preserved body begin 0005C9F1
00940   this->name = "PParameterFirstParametersPositionControl";
00941   this->lowerLimit = 0;
00942   this->upperLimit = INT_MAX;
00943   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00944   // Bouml preserved body end 0005C9F1
00945 }
00946 
00947 PParameterFirstParametersPositionControl::~PParameterFirstParametersPositionControl()
00948 {
00949   // Bouml preserved body begin 0005CA71
00950   // Bouml preserved body end 0005CA71
00951 }
00952 
00953 void PParameterFirstParametersPositionControl::getParameter(int& parameter) const
00954 {
00955   // Bouml preserved body begin 0005CAF1
00956   parameter = this->value;
00957   // Bouml preserved body end 0005CAF1
00958 }
00959 
00960 void PParameterFirstParametersPositionControl::setParameter(const int parameter)
00961 {
00962   // Bouml preserved body begin 0005CB71
00963   if (this->lowerLimit > parameter)
00964   {
00965     throw std::out_of_range("The parameter exceeds the lower limit");
00966   }
00967   if (this->upperLimit < parameter)
00968   {
00969     throw std::out_of_range("The parameter exceeds the upper limit");
00970   }
00971 
00972   this->value = parameter;
00973   // Bouml preserved body end 0005CB71
00974 }
00975 
00976 void PParameterFirstParametersPositionControl::toString(std::string& value)
00977 {
00978   // Bouml preserved body begin 0009CDF1
00979   std::stringstream ss;
00980   ss << this->name << ": " << this->value;
00981   value = ss.str();
00982   // Bouml preserved body end 0009CDF1
00983 }
00984 
00985 void PParameterFirstParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
00986                                                                    TMCLCommandNumber msgType,
00987                                                                    const YouBotJointStorage& storage) const
00988 {
00989   // Bouml preserved body begin 0005CBF1
00990 
00991   message.stctOutput.commandNumber = msgType;
00992   message.stctOutput.moduleAddress = DRIVE;
00993   message.stctOutput.typeNumber = 130; //PParameterFirstParametersPositionControl
00994   message.stctOutput.value = value;
00995 
00996   // Bouml preserved body end 0005CBF1
00997 }
00998 
00999 void PParameterFirstParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01000                                                                    const YouBotJointStorage& storage)
01001 {
01002   // Bouml preserved body begin 0005CC71
01003   this->value = (int32)message.stctInput.value;
01004   // Bouml preserved body end 0005CC71
01005 }
01006 
01007 IParameterFirstParametersPositionControl::IParameterFirstParametersPositionControl()
01008 {
01009   // Bouml preserved body begin 000699F1
01010   this->name = "IParameterFirstParametersPositionControl";
01011   this->lowerLimit = INT_MIN;
01012   this->upperLimit = INT_MAX;
01013   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01014   // Bouml preserved body end 000699F1
01015 }
01016 
01017 IParameterFirstParametersPositionControl::~IParameterFirstParametersPositionControl()
01018 {
01019   // Bouml preserved body begin 00069A71
01020   // Bouml preserved body end 00069A71
01021 }
01022 
01023 void IParameterFirstParametersPositionControl::getParameter(int& parameter) const
01024 {
01025   // Bouml preserved body begin 00069AF1
01026   parameter = this->value;
01027   // Bouml preserved body end 00069AF1
01028 }
01029 
01030 void IParameterFirstParametersPositionControl::setParameter(const int parameter)
01031 {
01032   // Bouml preserved body begin 00069B71
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 00069B71
01044 }
01045 
01046 void IParameterFirstParametersPositionControl::toString(std::string& value)
01047 {
01048   // Bouml preserved body begin 0009CE71
01049   std::stringstream ss;
01050   ss << this->name << ": " << this->value;
01051   value = ss.str();
01052   // Bouml preserved body end 0009CE71
01053 }
01054 
01055 void IParameterFirstParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01056                                                                    TMCLCommandNumber msgType,
01057                                                                    const YouBotJointStorage& storage) const
01058 {
01059   // Bouml preserved body begin 00069BF1
01060 
01061   message.stctOutput.commandNumber = msgType;
01062   message.stctOutput.moduleAddress = DRIVE;
01063   message.stctOutput.typeNumber = 131; //IParameterFirstParametersPositionControl
01064   message.stctOutput.value = value;
01065 
01066   // Bouml preserved body end 00069BF1
01067 }
01068 
01069 void IParameterFirstParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01070                                                                    const YouBotJointStorage& storage)
01071 {
01072   // Bouml preserved body begin 00069C71
01073   this->value = (int32)message.stctInput.value;
01074   // Bouml preserved body end 00069C71
01075 }
01076 
01077 DParameterFirstParametersPositionControl::DParameterFirstParametersPositionControl()
01078 {
01079   // Bouml preserved body begin 00069DF1
01080   this->name = "DParameterFirstParametersPositionControl";
01081   this->lowerLimit = INT_MIN;
01082   this->upperLimit = INT_MAX;
01083   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01084   // Bouml preserved body end 00069DF1
01085 }
01086 
01087 DParameterFirstParametersPositionControl::~DParameterFirstParametersPositionControl()
01088 {
01089   // Bouml preserved body begin 00069E71
01090   // Bouml preserved body end 00069E71
01091 }
01092 
01093 void DParameterFirstParametersPositionControl::getParameter(int& parameter) const
01094 {
01095   // Bouml preserved body begin 00069EF1
01096   parameter = this->value;
01097   // Bouml preserved body end 00069EF1
01098 }
01099 
01100 void DParameterFirstParametersPositionControl::setParameter(const int parameter)
01101 {
01102   // Bouml preserved body begin 00069F71
01103   if (this->lowerLimit > parameter)
01104   {
01105     throw std::out_of_range("The parameter exceeds the lower limit");
01106   }
01107   if (this->upperLimit < parameter)
01108   {
01109     throw std::out_of_range("The parameter exceeds the upper limit");
01110   }
01111 
01112   this->value = parameter;
01113   // Bouml preserved body end 00069F71
01114 }
01115 
01116 void DParameterFirstParametersPositionControl::toString(std::string& value)
01117 {
01118   // Bouml preserved body begin 0009CEF1
01119   std::stringstream ss;
01120   ss << this->name << ": " << this->value;
01121   value = ss.str();
01122   // Bouml preserved body end 0009CEF1
01123 }
01124 
01125 void DParameterFirstParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01126                                                                    TMCLCommandNumber msgType,
01127                                                                    const YouBotJointStorage& storage) const
01128 {
01129   // Bouml preserved body begin 00069FF1
01130 
01131   message.stctOutput.commandNumber = msgType;
01132   message.stctOutput.moduleAddress = DRIVE;
01133   message.stctOutput.typeNumber = 132; //DParameterFirstParametersPositionControl
01134   message.stctOutput.value = value;
01135 
01136   // Bouml preserved body end 00069FF1
01137 }
01138 
01139 void DParameterFirstParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01140                                                                    const YouBotJointStorage& storage)
01141 {
01142   // Bouml preserved body begin 0006A071
01143   this->value = (int32)message.stctInput.value;
01144   // Bouml preserved body end 0006A071
01145 }
01146 
01147 IClippingParameterFirstParametersPositionControl::IClippingParameterFirstParametersPositionControl()
01148 {
01149   // Bouml preserved body begin 0006B1F1
01150   this->name = "IClippingParameterFirstParametersPositionControl";
01151   this->lowerLimit = INT_MIN;
01152   this->upperLimit = INT_MAX;
01153   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01154   // Bouml preserved body end 0006B1F1
01155 }
01156 
01157 IClippingParameterFirstParametersPositionControl::~IClippingParameterFirstParametersPositionControl()
01158 {
01159   // Bouml preserved body begin 0006B271
01160   // Bouml preserved body end 0006B271
01161 }
01162 
01163 void IClippingParameterFirstParametersPositionControl::getParameter(int& parameter) const
01164 {
01165   // Bouml preserved body begin 0006B2F1
01166   parameter = this->value;
01167   // Bouml preserved body end 0006B2F1
01168 }
01169 
01170 void IClippingParameterFirstParametersPositionControl::setParameter(const int parameter)
01171 {
01172   // Bouml preserved body begin 0006B371
01173   if (this->lowerLimit > parameter)
01174   {
01175     throw std::out_of_range("The parameter exceeds the lower limit");
01176   }
01177   if (this->upperLimit < parameter)
01178   {
01179     throw std::out_of_range("The parameter exceeds the upper limit");
01180   }
01181 
01182   this->value = parameter;
01183   // Bouml preserved body end 0006B371
01184 }
01185 
01186 void IClippingParameterFirstParametersPositionControl::toString(std::string& value)
01187 {
01188   // Bouml preserved body begin 0009D071
01189   std::stringstream ss;
01190   ss << this->name << ": " << this->value;
01191   value = ss.str();
01192   // Bouml preserved body end 0009D071
01193 }
01194 
01195 void IClippingParameterFirstParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01196                                                                            TMCLCommandNumber msgType,
01197                                                                            const YouBotJointStorage& storage) const
01198 {
01199   // Bouml preserved body begin 0006B3F1
01200 
01201   message.stctOutput.commandNumber = msgType;
01202   message.stctOutput.moduleAddress = DRIVE;
01203   message.stctOutput.typeNumber = 135; //IClippingParameterFirstParametersPositionControl
01204   message.stctOutput.value = value;
01205 
01206   // Bouml preserved body end 0006B3F1
01207 }
01208 
01209 void IClippingParameterFirstParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01210                                                                            const YouBotJointStorage& storage)
01211 {
01212   // Bouml preserved body begin 0006B471
01213   this->value = (int32)message.stctInput.value;
01214   // Bouml preserved body end 0006B471
01215 }
01216 
01217 PParameterFirstParametersSpeedControl::PParameterFirstParametersSpeedControl()
01218 {
01219   // Bouml preserved body begin 0006B5F1
01220   this->name = "PParameterFirstParametersSpeedControl";
01221   this->lowerLimit = INT_MIN;
01222   this->upperLimit = INT_MAX;
01223   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01224   // Bouml preserved body end 0006B5F1
01225 }
01226 
01227 PParameterFirstParametersSpeedControl::~PParameterFirstParametersSpeedControl()
01228 {
01229   // Bouml preserved body begin 0006B671
01230   // Bouml preserved body end 0006B671
01231 }
01232 
01233 void PParameterFirstParametersSpeedControl::getParameter(int& parameter) const
01234 {
01235   // Bouml preserved body begin 0006B6F1
01236   parameter = this->value;
01237   // Bouml preserved body end 0006B6F1
01238 }
01239 
01240 void PParameterFirstParametersSpeedControl::setParameter(const int parameter)
01241 {
01242   // Bouml preserved body begin 0006B771
01243   if (this->lowerLimit > parameter)
01244   {
01245     throw std::out_of_range("The parameter exceeds the lower limit");
01246   }
01247   if (this->upperLimit < parameter)
01248   {
01249     throw std::out_of_range("The parameter exceeds the upper limit");
01250   }
01251 
01252   this->value = parameter;
01253   // Bouml preserved body end 0006B771
01254 }
01255 
01256 void PParameterFirstParametersSpeedControl::toString(std::string& value)
01257 {
01258   // Bouml preserved body begin 0009D271
01259   std::stringstream ss;
01260   ss << this->name << ": " << this->value;
01261   value = ss.str();
01262   // Bouml preserved body end 0009D271
01263 }
01264 
01265 void PParameterFirstParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01266                                                                 TMCLCommandNumber msgType,
01267                                                                 const YouBotJointStorage& storage) const
01268 {
01269   // Bouml preserved body begin 0006B7F1
01270 
01271   message.stctOutput.commandNumber = msgType;
01272   message.stctOutput.moduleAddress = DRIVE;
01273   message.stctOutput.typeNumber = 140; //PParameterFirstParametersSpeedControl
01274   message.stctOutput.value = value;
01275 
01276   // Bouml preserved body end 0006B7F1
01277 }
01278 
01279 void PParameterFirstParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01280                                                                 const YouBotJointStorage& storage)
01281 {
01282   // Bouml preserved body begin 0006B871
01283   this->value = (int32)message.stctInput.value;
01284   // Bouml preserved body end 0006B871
01285 }
01286 
01287 IParameterFirstParametersSpeedControl::IParameterFirstParametersSpeedControl()
01288 {
01289   // Bouml preserved body begin 0006B9F1
01290   this->name = "IParameterFirstParametersSpeedControl";
01291   this->lowerLimit = INT_MIN;
01292   this->upperLimit = INT_MAX;
01293   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01294   // Bouml preserved body end 0006B9F1
01295 }
01296 
01297 IParameterFirstParametersSpeedControl::~IParameterFirstParametersSpeedControl()
01298 {
01299   // Bouml preserved body begin 0006BA71
01300   // Bouml preserved body end 0006BA71
01301 }
01302 
01303 void IParameterFirstParametersSpeedControl::getParameter(int& parameter) const
01304 {
01305   // Bouml preserved body begin 0006BAF1
01306   parameter = this->value;
01307   // Bouml preserved body end 0006BAF1
01308 }
01309 
01310 void IParameterFirstParametersSpeedControl::setParameter(const int parameter)
01311 {
01312   // Bouml preserved body begin 0006BB71
01313   if (this->lowerLimit > parameter)
01314   {
01315     throw std::out_of_range("The parameter exceeds the lower limit");
01316   }
01317   if (this->upperLimit < parameter)
01318   {
01319     throw std::out_of_range("The parameter exceeds the upper limit");
01320   }
01321 
01322   this->value = parameter;
01323   // Bouml preserved body end 0006BB71
01324 }
01325 
01326 void IParameterFirstParametersSpeedControl::toString(std::string& value)
01327 {
01328   // Bouml preserved body begin 0009D2F1
01329   std::stringstream ss;
01330   ss << this->name << ": " << this->value;
01331   value = ss.str();
01332   // Bouml preserved body end 0009D2F1
01333 }
01334 
01335 void IParameterFirstParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01336                                                                 TMCLCommandNumber msgType,
01337                                                                 const YouBotJointStorage& storage) const
01338 {
01339   // Bouml preserved body begin 0006BBF1
01340 
01341   message.stctOutput.commandNumber = msgType;
01342   message.stctOutput.moduleAddress = DRIVE;
01343   message.stctOutput.typeNumber = 141; //IParameterFirstParametersSpeedControl
01344   message.stctOutput.value = value;
01345 
01346   // Bouml preserved body end 0006BBF1
01347 }
01348 
01349 void IParameterFirstParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01350                                                                 const YouBotJointStorage& storage)
01351 {
01352   // Bouml preserved body begin 0006BC71
01353   this->value = (int32)message.stctInput.value;
01354   // Bouml preserved body end 0006BC71
01355 }
01356 
01357 DParameterFirstParametersSpeedControl::DParameterFirstParametersSpeedControl()
01358 {
01359   // Bouml preserved body begin 0006BDF1
01360   this->name = "DParameterFirstParametersSpeedControl";
01361   this->lowerLimit = INT_MIN;
01362   this->upperLimit = INT_MAX;
01363   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01364   // Bouml preserved body end 0006BDF1
01365 }
01366 
01367 DParameterFirstParametersSpeedControl::~DParameterFirstParametersSpeedControl()
01368 {
01369   // Bouml preserved body begin 0006BE71
01370   // Bouml preserved body end 0006BE71
01371 }
01372 
01373 void DParameterFirstParametersSpeedControl::getParameter(int& parameter) const
01374 {
01375   // Bouml preserved body begin 0006BEF1
01376   parameter = this->value;
01377   // Bouml preserved body end 0006BEF1
01378 }
01379 
01380 void DParameterFirstParametersSpeedControl::setParameter(const int parameter)
01381 {
01382   // Bouml preserved body begin 0006BF71
01383   if (this->lowerLimit > parameter)
01384   {
01385     throw std::out_of_range("The parameter exceeds the lower limit");
01386   }
01387   if (this->upperLimit < parameter)
01388   {
01389     throw std::out_of_range("The parameter exceeds the upper limit");
01390   }
01391 
01392   this->value = parameter;
01393   // Bouml preserved body end 0006BF71
01394 }
01395 
01396 void DParameterFirstParametersSpeedControl::toString(std::string& value)
01397 {
01398   // Bouml preserved body begin 0009D371
01399   std::stringstream ss;
01400   ss << this->name << ": " << this->value;
01401   value = ss.str();
01402   // Bouml preserved body end 0009D371
01403 }
01404 
01405 void DParameterFirstParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01406                                                                 TMCLCommandNumber msgType,
01407                                                                 const YouBotJointStorage& storage) const
01408 {
01409   // Bouml preserved body begin 0006BFF1
01410 
01411   message.stctOutput.commandNumber = msgType;
01412   message.stctOutput.moduleAddress = DRIVE;
01413   message.stctOutput.typeNumber = 142; //DParameterFirstParametersSpeedControl
01414   message.stctOutput.value = value;
01415 
01416   // Bouml preserved body end 0006BFF1
01417 }
01418 
01419 void DParameterFirstParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01420                                                                 const YouBotJointStorage& storage)
01421 {
01422   // Bouml preserved body begin 0006C071
01423   this->value = (int32)message.stctInput.value;
01424   // Bouml preserved body end 0006C071
01425 }
01426 
01427 IClippingParameterFirstParametersSpeedControl::IClippingParameterFirstParametersSpeedControl()
01428 {
01429   // Bouml preserved body begin 0006C1F1
01430   this->name = "IClippingParameterFirstParametersSpeedControl";
01431   this->lowerLimit = INT_MIN;
01432   this->upperLimit = INT_MAX;
01433   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01434   // Bouml preserved body end 0006C1F1
01435 }
01436 
01437 IClippingParameterFirstParametersSpeedControl::~IClippingParameterFirstParametersSpeedControl()
01438 {
01439   // Bouml preserved body begin 0006C271
01440   // Bouml preserved body end 0006C271
01441 }
01442 
01443 void IClippingParameterFirstParametersSpeedControl::getParameter(int& parameter) const
01444 {
01445   // Bouml preserved body begin 0006C2F1
01446   parameter = this->value;
01447   // Bouml preserved body end 0006C2F1
01448 }
01449 
01450 void IClippingParameterFirstParametersSpeedControl::setParameter(const int parameter)
01451 {
01452   // Bouml preserved body begin 0006C371
01453   if (this->lowerLimit > parameter)
01454   {
01455     throw std::out_of_range("The parameter exceeds the lower limit");
01456   }
01457   if (this->upperLimit < parameter)
01458   {
01459     throw std::out_of_range("The parameter exceeds the upper limit");
01460   }
01461 
01462   this->value = parameter;
01463   // Bouml preserved body end 0006C371
01464 }
01465 
01466 void IClippingParameterFirstParametersSpeedControl::toString(std::string& value)
01467 {
01468   // Bouml preserved body begin 0009D3F1
01469   std::stringstream ss;
01470   ss << this->name << ": " << this->value;
01471   value = ss.str();
01472   // Bouml preserved body end 0009D3F1
01473 }
01474 
01475 void IClippingParameterFirstParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01476                                                                         TMCLCommandNumber msgType,
01477                                                                         const YouBotJointStorage& storage) const
01478 {
01479   // Bouml preserved body begin 0006C3F1
01480 
01481   message.stctOutput.commandNumber = msgType;
01482   message.stctOutput.moduleAddress = DRIVE;
01483   message.stctOutput.typeNumber = 143; //IClippingParameterFirstParametersSpeedControl
01484   message.stctOutput.value = value;
01485 
01486   // Bouml preserved body end 0006C3F1
01487 }
01488 
01489 void IClippingParameterFirstParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01490                                                                         const YouBotJointStorage& storage)
01491 {
01492   // Bouml preserved body begin 0006C471
01493   this->value = (int32)message.stctInput.value;
01494   // Bouml preserved body end 0006C471
01495 }
01496 
01497 PParameterSecondParametersPositionControl::PParameterSecondParametersPositionControl()
01498 {
01499   // Bouml preserved body begin 0006CDF1
01500   this->name = "PParameterSecondParametersPositionControl";
01501   this->lowerLimit = INT_MIN;
01502   this->upperLimit = INT_MAX;
01503   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01504   // Bouml preserved body end 0006CDF1
01505 }
01506 
01507 PParameterSecondParametersPositionControl::~PParameterSecondParametersPositionControl()
01508 {
01509   // Bouml preserved body begin 0006CE71
01510   // Bouml preserved body end 0006CE71
01511 }
01512 
01513 void PParameterSecondParametersPositionControl::getParameter(int& parameter) const
01514 {
01515   // Bouml preserved body begin 0006CEF1
01516   parameter = this->value;
01517   // Bouml preserved body end 0006CEF1
01518 }
01519 
01520 void PParameterSecondParametersPositionControl::setParameter(const int parameter)
01521 {
01522   // Bouml preserved body begin 0006CF71
01523   if (this->lowerLimit > parameter)
01524   {
01525     throw std::out_of_range("The parameter exceeds the lower limit");
01526   }
01527   if (this->upperLimit < parameter)
01528   {
01529     throw std::out_of_range("The parameter exceeds the upper limit");
01530   }
01531 
01532   this->value = parameter;
01533   // Bouml preserved body end 0006CF71
01534 }
01535 
01536 void PParameterSecondParametersPositionControl::toString(std::string& value)
01537 {
01538   // Bouml preserved body begin 0009DD71
01539   std::stringstream ss;
01540   ss << this->name << ": " << this->value;
01541   value = ss.str();
01542   // Bouml preserved body end 0009DD71
01543 }
01544 
01545 void PParameterSecondParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01546                                                                     TMCLCommandNumber msgType,
01547                                                                     const YouBotJointStorage& storage) const
01548 {
01549   // Bouml preserved body begin 0006CFF1
01550 
01551   message.stctOutput.commandNumber = msgType;
01552   message.stctOutput.moduleAddress = DRIVE;
01553   message.stctOutput.typeNumber = 230; //PParameterSecondParametersPositionControl
01554   message.stctOutput.value = value;
01555 
01556   // Bouml preserved body end 0006CFF1
01557 }
01558 
01559 void PParameterSecondParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01560                                                                     const YouBotJointStorage& storage)
01561 {
01562   // Bouml preserved body begin 0006D071
01563   this->value = (int32)message.stctInput.value;
01564   // Bouml preserved body end 0006D071
01565 }
01566 
01567 IParameterSecondParametersPositionControl::IParameterSecondParametersPositionControl()
01568 {
01569   // Bouml preserved body begin 0006D1F1
01570   this->name = "IParameterSecondParametersPositionControl";
01571   this->lowerLimit = INT_MIN;
01572   this->upperLimit = INT_MAX;
01573   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01574   // Bouml preserved body end 0006D1F1
01575 }
01576 
01577 IParameterSecondParametersPositionControl::~IParameterSecondParametersPositionControl()
01578 {
01579   // Bouml preserved body begin 0006D271
01580   // Bouml preserved body end 0006D271
01581 }
01582 
01583 void IParameterSecondParametersPositionControl::getParameter(int& parameter) const
01584 {
01585   // Bouml preserved body begin 0006D2F1
01586   parameter = this->value;
01587   // Bouml preserved body end 0006D2F1
01588 }
01589 
01590 void IParameterSecondParametersPositionControl::setParameter(const int parameter)
01591 {
01592   // Bouml preserved body begin 0006D371
01593   if (this->lowerLimit > parameter)
01594   {
01595     throw std::out_of_range("The parameter exceeds the lower limit");
01596   }
01597   if (this->upperLimit < parameter)
01598   {
01599     throw std::out_of_range("The parameter exceeds the upper limit");
01600   }
01601 
01602   this->value = parameter;
01603   // Bouml preserved body end 0006D371
01604 }
01605 
01606 void IParameterSecondParametersPositionControl::toString(std::string& value)
01607 {
01608   // Bouml preserved body begin 0009DDF1
01609   std::stringstream ss;
01610   ss << this->name << ": " << this->value;
01611   value = ss.str();
01612   // Bouml preserved body end 0009DDF1
01613 }
01614 
01615 void IParameterSecondParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01616                                                                     TMCLCommandNumber msgType,
01617                                                                     const YouBotJointStorage& storage) const
01618 {
01619   // Bouml preserved body begin 0006D3F1
01620 
01621   message.stctOutput.commandNumber = msgType;
01622   message.stctOutput.moduleAddress = DRIVE;
01623   message.stctOutput.typeNumber = 231; //IParameterSecondParametersPositionControl
01624   message.stctOutput.value = value;
01625 
01626   // Bouml preserved body end 0006D3F1
01627 }
01628 
01629 void IParameterSecondParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01630                                                                     const YouBotJointStorage& storage)
01631 {
01632   // Bouml preserved body begin 0006D471
01633   this->value = (int32)message.stctInput.value;
01634   // Bouml preserved body end 0006D471
01635 }
01636 
01637 DParameterSecondParametersPositionControl::DParameterSecondParametersPositionControl()
01638 {
01639   // Bouml preserved body begin 0006D5F1
01640   this->name = "DParameterSecondParametersPositionControl";
01641   this->lowerLimit = INT_MIN;
01642   this->upperLimit = INT_MAX;
01643   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01644   // Bouml preserved body end 0006D5F1
01645 }
01646 
01647 DParameterSecondParametersPositionControl::~DParameterSecondParametersPositionControl()
01648 {
01649   // Bouml preserved body begin 0006D671
01650   // Bouml preserved body end 0006D671
01651 }
01652 
01653 void DParameterSecondParametersPositionControl::getParameter(int& parameter) const
01654 {
01655   // Bouml preserved body begin 0006D6F1
01656   parameter = this->value;
01657   // Bouml preserved body end 0006D6F1
01658 }
01659 
01660 void DParameterSecondParametersPositionControl::setParameter(const int parameter)
01661 {
01662   // Bouml preserved body begin 0006D771
01663   if (this->lowerLimit > parameter)
01664   {
01665     throw std::out_of_range("The parameter exceeds the lower limit");
01666   }
01667   if (this->upperLimit < parameter)
01668   {
01669     throw std::out_of_range("The parameter exceeds the upper limit");
01670   }
01671 
01672   this->value = parameter;
01673   // Bouml preserved body end 0006D771
01674 }
01675 
01676 void DParameterSecondParametersPositionControl::toString(std::string& value)
01677 {
01678   // Bouml preserved body begin 0009DE71
01679   std::stringstream ss;
01680   ss << this->name << ": " << this->value;
01681   value = ss.str();
01682   // Bouml preserved body end 0009DE71
01683 }
01684 
01685 void DParameterSecondParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01686                                                                     TMCLCommandNumber msgType,
01687                                                                     const YouBotJointStorage& storage) const
01688 {
01689   // Bouml preserved body begin 0006D7F1
01690 
01691   message.stctOutput.commandNumber = msgType;
01692   message.stctOutput.moduleAddress = DRIVE;
01693   message.stctOutput.typeNumber = 232; //DParameterSecondParametersPositionControl
01694   message.stctOutput.value = value;
01695 
01696   // Bouml preserved body end 0006D7F1
01697 }
01698 
01699 void DParameterSecondParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01700                                                                     const YouBotJointStorage& storage)
01701 {
01702   // Bouml preserved body begin 0006D871
01703   this->value = (int32)message.stctInput.value;
01704   // Bouml preserved body end 0006D871
01705 }
01706 
01707 IClippingParameterSecondParametersPositionControl::IClippingParameterSecondParametersPositionControl()
01708 {
01709   // Bouml preserved body begin 0006D9F1
01710   this->name = "IClippingParameterSecondParametersPositionControl";
01711   this->lowerLimit = INT_MIN;
01712   this->upperLimit = INT_MAX;
01713   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01714   // Bouml preserved body end 0006D9F1
01715 }
01716 
01717 IClippingParameterSecondParametersPositionControl::~IClippingParameterSecondParametersPositionControl()
01718 {
01719   // Bouml preserved body begin 0006DA71
01720   // Bouml preserved body end 0006DA71
01721 }
01722 
01723 void IClippingParameterSecondParametersPositionControl::getParameter(int& parameter) const
01724 {
01725   // Bouml preserved body begin 0006DAF1
01726   parameter = this->value;
01727   // Bouml preserved body end 0006DAF1
01728 }
01729 
01730 void IClippingParameterSecondParametersPositionControl::setParameter(const int parameter)
01731 {
01732   // Bouml preserved body begin 0006DB71
01733   if (this->lowerLimit > parameter)
01734   {
01735     throw std::out_of_range("The parameter exceeds the lower limit");
01736   }
01737   if (this->upperLimit < parameter)
01738   {
01739     throw std::out_of_range("The parameter exceeds the upper limit");
01740   }
01741 
01742   this->value = parameter;
01743   // Bouml preserved body end 0006DB71
01744 }
01745 
01746 void IClippingParameterSecondParametersPositionControl::toString(std::string& value)
01747 {
01748   // Bouml preserved body begin 0009DEF1
01749   std::stringstream ss;
01750   ss << this->name << ": " << this->value;
01751   value = ss.str();
01752   // Bouml preserved body end 0009DEF1
01753 }
01754 
01755 void IClippingParameterSecondParametersPositionControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01756                                                                             TMCLCommandNumber msgType,
01757                                                                             const YouBotJointStorage& storage) const
01758 {
01759   // Bouml preserved body begin 0006DBF1
01760 
01761   message.stctOutput.commandNumber = msgType;
01762   message.stctOutput.moduleAddress = DRIVE;
01763   message.stctOutput.typeNumber = 233; //IClippingParameterSecondParametersPositionControl
01764   message.stctOutput.value = value;
01765 
01766   // Bouml preserved body end 0006DBF1
01767 }
01768 
01769 void IClippingParameterSecondParametersPositionControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01770                                                                             const YouBotJointStorage& storage)
01771 {
01772   // Bouml preserved body begin 0006DC71
01773   this->value = (int32)message.stctInput.value;
01774   // Bouml preserved body end 0006DC71
01775 }
01776 
01777 PParameterSecondParametersSpeedControl::PParameterSecondParametersSpeedControl()
01778 {
01779   // Bouml preserved body begin 0006DDF1
01780   this->name = "PParameterSecondParametersSpeedControl";
01781   this->lowerLimit = INT_MIN;
01782   this->upperLimit = INT_MAX;
01783   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01784   // Bouml preserved body end 0006DDF1
01785 }
01786 
01787 PParameterSecondParametersSpeedControl::~PParameterSecondParametersSpeedControl()
01788 {
01789   // Bouml preserved body begin 0006DE71
01790   // Bouml preserved body end 0006DE71
01791 }
01792 
01793 void PParameterSecondParametersSpeedControl::getParameter(int& parameter) const
01794 {
01795   // Bouml preserved body begin 0006DEF1
01796   parameter = this->value;
01797   // Bouml preserved body end 0006DEF1
01798 }
01799 
01800 void PParameterSecondParametersSpeedControl::setParameter(const int parameter)
01801 {
01802   // Bouml preserved body begin 0006DF71
01803   if (this->lowerLimit > parameter)
01804   {
01805     throw std::out_of_range("The parameter exceeds the lower limit");
01806   }
01807   if (this->upperLimit < parameter)
01808   {
01809     throw std::out_of_range("The parameter exceeds the upper limit");
01810   }
01811 
01812   this->value = parameter;
01813   // Bouml preserved body end 0006DF71
01814 }
01815 
01816 void PParameterSecondParametersSpeedControl::toString(std::string& value)
01817 {
01818   // Bouml preserved body begin 0009DF71
01819   std::stringstream ss;
01820   ss << this->name << ": " << this->value;
01821   value = ss.str();
01822   // Bouml preserved body end 0009DF71
01823 }
01824 
01825 void PParameterSecondParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01826                                                                  TMCLCommandNumber msgType,
01827                                                                  const YouBotJointStorage& storage) const
01828 {
01829   // Bouml preserved body begin 0006DFF1
01830 
01831   message.stctOutput.commandNumber = msgType;
01832   message.stctOutput.moduleAddress = DRIVE;
01833   message.stctOutput.typeNumber = 234; //PParameterSecondParametersSpeedControl
01834   message.stctOutput.value = value;
01835 
01836   // Bouml preserved body end 0006DFF1
01837 }
01838 
01839 void PParameterSecondParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01840                                                                  const YouBotJointStorage& storage)
01841 {
01842   // Bouml preserved body begin 0006E071
01843   this->value = (int32)message.stctInput.value;
01844   // Bouml preserved body end 0006E071
01845 }
01846 
01847 IParameterSecondParametersSpeedControl::IParameterSecondParametersSpeedControl()
01848 {
01849   // Bouml preserved body begin 0006E1F1
01850   this->name = "IParameterSecondParametersSpeedControl";
01851   this->lowerLimit = INT_MIN;
01852   this->upperLimit = INT_MAX;
01853   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01854   // Bouml preserved body end 0006E1F1
01855 }
01856 
01857 IParameterSecondParametersSpeedControl::~IParameterSecondParametersSpeedControl()
01858 {
01859   // Bouml preserved body begin 0006E271
01860   // Bouml preserved body end 0006E271
01861 }
01862 
01863 void IParameterSecondParametersSpeedControl::getParameter(int& parameter) const
01864 {
01865   // Bouml preserved body begin 0006E2F1
01866   parameter = this->value;
01867   // Bouml preserved body end 0006E2F1
01868 }
01869 
01870 void IParameterSecondParametersSpeedControl::setParameter(const int parameter)
01871 {
01872   // Bouml preserved body begin 0006E371
01873   if (this->lowerLimit > parameter)
01874   {
01875     throw std::out_of_range("The parameter exceeds the lower limit");
01876   }
01877   if (this->upperLimit < parameter)
01878   {
01879     throw std::out_of_range("The parameter exceeds the upper limit");
01880   }
01881 
01882   this->value = parameter;
01883   // Bouml preserved body end 0006E371
01884 }
01885 
01886 void IParameterSecondParametersSpeedControl::toString(std::string& value)
01887 {
01888   // Bouml preserved body begin 0009DFF1
01889   std::stringstream ss;
01890   ss << this->name << ": " << this->value;
01891   value = ss.str();
01892   // Bouml preserved body end 0009DFF1
01893 }
01894 
01895 void IParameterSecondParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01896                                                                  TMCLCommandNumber msgType,
01897                                                                  const YouBotJointStorage& storage) const
01898 {
01899   // Bouml preserved body begin 0006E3F1
01900 
01901   message.stctOutput.commandNumber = msgType;
01902   message.stctOutput.moduleAddress = DRIVE;
01903   message.stctOutput.typeNumber = 235; //IParameterSecondParametersSpeedControl
01904   message.stctOutput.value = value;
01905 
01906   // Bouml preserved body end 0006E3F1
01907 }
01908 
01909 void IParameterSecondParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01910                                                                  const YouBotJointStorage& storage)
01911 {
01912   // Bouml preserved body begin 0006E471
01913   this->value = (int32)message.stctInput.value;
01914   // Bouml preserved body end 0006E471
01915 }
01916 
01917 DParameterSecondParametersSpeedControl::DParameterSecondParametersSpeedControl()
01918 {
01919   // Bouml preserved body begin 0006E5F1
01920   this->name = "DParameterSecondParametersSpeedControl";
01921   this->lowerLimit = INT_MIN;
01922   this->upperLimit = INT_MAX;
01923   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01924   // Bouml preserved body end 0006E5F1
01925 }
01926 
01927 DParameterSecondParametersSpeedControl::~DParameterSecondParametersSpeedControl()
01928 {
01929   // Bouml preserved body begin 0006E671
01930   // Bouml preserved body end 0006E671
01931 }
01932 
01933 void DParameterSecondParametersSpeedControl::getParameter(int& parameter) const
01934 {
01935   // Bouml preserved body begin 0006E6F1
01936   parameter = this->value;
01937   // Bouml preserved body end 0006E6F1
01938 }
01939 
01940 void DParameterSecondParametersSpeedControl::setParameter(const int parameter)
01941 {
01942   // Bouml preserved body begin 0006E771
01943   if (this->lowerLimit > parameter)
01944   {
01945     throw std::out_of_range("The parameter exceeds the lower limit");
01946   }
01947   if (this->upperLimit < parameter)
01948   {
01949     throw std::out_of_range("The parameter exceeds the upper limit");
01950   }
01951 
01952   this->value = parameter;
01953   // Bouml preserved body end 0006E771
01954 }
01955 
01956 void DParameterSecondParametersSpeedControl::toString(std::string& value)
01957 {
01958   // Bouml preserved body begin 0009E071
01959   std::stringstream ss;
01960   ss << this->name << ": " << this->value;
01961   value = ss.str();
01962   // Bouml preserved body end 0009E071
01963 }
01964 
01965 void DParameterSecondParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
01966                                                                  TMCLCommandNumber msgType,
01967                                                                  const YouBotJointStorage& storage) const
01968 {
01969   // Bouml preserved body begin 0006E7F1
01970 
01971   message.stctOutput.commandNumber = msgType;
01972   message.stctOutput.moduleAddress = DRIVE;
01973   message.stctOutput.typeNumber = 236; //DParameterSecondParametersSpeedControl
01974   message.stctOutput.value = value;
01975 
01976   // Bouml preserved body end 0006E7F1
01977 }
01978 
01979 void DParameterSecondParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
01980                                                                  const YouBotJointStorage& storage)
01981 {
01982   // Bouml preserved body begin 0006E871
01983   this->value = (int32)message.stctInput.value;
01984   // Bouml preserved body end 0006E871
01985 }
01986 
01987 IClippingParameterSecondParametersSpeedControl::IClippingParameterSecondParametersSpeedControl()
01988 {
01989   // Bouml preserved body begin 0006E9F1
01990   this->name = "IClippingParameterSecondParametersSpeedControl";
01991   this->lowerLimit = INT_MIN;
01992   this->upperLimit = INT_MAX;
01993   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
01994   // Bouml preserved body end 0006E9F1
01995 }
01996 
01997 IClippingParameterSecondParametersSpeedControl::~IClippingParameterSecondParametersSpeedControl()
01998 {
01999   // Bouml preserved body begin 0006EA71
02000   // Bouml preserved body end 0006EA71
02001 }
02002 
02003 void IClippingParameterSecondParametersSpeedControl::getParameter(int& parameter) const
02004 {
02005   // Bouml preserved body begin 0006EAF1
02006   parameter = this->value;
02007   // Bouml preserved body end 0006EAF1
02008 }
02009 
02010 void IClippingParameterSecondParametersSpeedControl::setParameter(const int parameter)
02011 {
02012   // Bouml preserved body begin 0006EB71
02013   if (this->lowerLimit > parameter)
02014   {
02015     throw std::out_of_range("The parameter exceeds the lower limit");
02016   }
02017   if (this->upperLimit < parameter)
02018   {
02019     throw std::out_of_range("The parameter exceeds the upper limit");
02020   }
02021 
02022   this->value = parameter;
02023   // Bouml preserved body end 0006EB71
02024 }
02025 
02026 void IClippingParameterSecondParametersSpeedControl::toString(std::string& value)
02027 {
02028   // Bouml preserved body begin 0009E0F1
02029   std::stringstream ss;
02030   ss << this->name << ": " << this->value;
02031   value = ss.str();
02032   // Bouml preserved body end 0009E0F1
02033 }
02034 
02035 void IClippingParameterSecondParametersSpeedControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message,
02036                                                                          TMCLCommandNumber msgType,
02037                                                                          const YouBotJointStorage& storage) const
02038 {
02039   // Bouml preserved body begin 0006EBF1
02040 
02041   message.stctOutput.commandNumber = msgType;
02042   message.stctOutput.moduleAddress = DRIVE;
02043   message.stctOutput.typeNumber = 237; //IClippingParameterSecondParametersSpeedControl
02044   message.stctOutput.value = value;
02045 
02046   // Bouml preserved body end 0006EBF1
02047 }
02048 
02049 void IClippingParameterSecondParametersSpeedControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02050                                                                          const YouBotJointStorage& storage)
02051 {
02052   // Bouml preserved body begin 0006EC71
02053   this->value = (int32)message.stctInput.value;
02054   // Bouml preserved body end 0006EC71
02055 }
02056 
02057 PParameterCurrentControl::PParameterCurrentControl()
02058 {
02059   // Bouml preserved body begin 00080371
02060   this->name = "PParameterCurrentControl";
02061   this->lowerLimit = INT_MIN;
02062   this->upperLimit = INT_MAX;
02063   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02064   // Bouml preserved body end 00080371
02065 }
02066 
02067 PParameterCurrentControl::~PParameterCurrentControl()
02068 {
02069   // Bouml preserved body begin 000803F1
02070   // Bouml preserved body end 000803F1
02071 }
02072 
02073 void PParameterCurrentControl::getParameter(int& parameter) const
02074 {
02075   // Bouml preserved body begin 00080471
02076   parameter = this->value;
02077   // Bouml preserved body end 00080471
02078 }
02079 
02080 void PParameterCurrentControl::setParameter(const int parameter)
02081 {
02082   // Bouml preserved body begin 000804F1
02083   if (this->lowerLimit > parameter)
02084   {
02085     throw std::out_of_range("The parameter exceeds the lower limit");
02086   }
02087   if (this->upperLimit < parameter)
02088   {
02089     throw std::out_of_range("The parameter exceeds the upper limit");
02090   }
02091 
02092   this->value = parameter;
02093   // Bouml preserved body end 000804F1
02094 }
02095 
02096 void PParameterCurrentControl::toString(std::string& value)
02097 {
02098   // Bouml preserved body begin 0009DA71
02099   std::stringstream ss;
02100   ss << this->name << ": " << this->value;
02101   value = ss.str();
02102   // Bouml preserved body end 0009DA71
02103 }
02104 
02105 void PParameterCurrentControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02106                                                    const YouBotJointStorage& storage) const
02107 {
02108   // Bouml preserved body begin 00080571
02109 
02110   message.stctOutput.commandNumber = msgType;
02111   message.stctOutput.moduleAddress = DRIVE;
02112   message.stctOutput.typeNumber = 172; //PParameterCurrentControl
02113   message.stctOutput.value = value;
02114 
02115   // Bouml preserved body end 00080571
02116 }
02117 
02118 void PParameterCurrentControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02119                                                    const YouBotJointStorage& storage)
02120 {
02121   // Bouml preserved body begin 000805F1
02122   this->value = (int32)message.stctInput.value;
02123   // Bouml preserved body end 000805F1
02124 }
02125 
02126 IParameterCurrentControl::IParameterCurrentControl()
02127 {
02128   // Bouml preserved body begin 00080771
02129   this->name = "IParameterCurrentControl";
02130   this->lowerLimit = INT_MIN;
02131   this->upperLimit = INT_MAX;
02132   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02133   // Bouml preserved body end 00080771
02134 }
02135 
02136 IParameterCurrentControl::~IParameterCurrentControl()
02137 {
02138   // Bouml preserved body begin 000807F1
02139   // Bouml preserved body end 000807F1
02140 }
02141 
02142 void IParameterCurrentControl::getParameter(int& parameter) const
02143 {
02144   // Bouml preserved body begin 00080871
02145   parameter = this->value;
02146   // Bouml preserved body end 00080871
02147 }
02148 
02149 void IParameterCurrentControl::setParameter(const int parameter)
02150 {
02151   // Bouml preserved body begin 000808F1
02152   if (this->lowerLimit > parameter)
02153   {
02154     throw std::out_of_range("The parameter exceeds the lower limit");
02155   }
02156   if (this->upperLimit < parameter)
02157   {
02158     throw std::out_of_range("The parameter exceeds the upper limit");
02159   }
02160 
02161   this->value = parameter;
02162   // Bouml preserved body end 000808F1
02163 }
02164 
02165 void IParameterCurrentControl::toString(std::string& value)
02166 {
02167   // Bouml preserved body begin 0009DAF1
02168   std::stringstream ss;
02169   ss << this->name << ": " << this->value;
02170   value = ss.str();
02171   // Bouml preserved body end 0009DAF1
02172 }
02173 
02174 void IParameterCurrentControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02175                                                    const YouBotJointStorage& storage) const
02176 {
02177   // Bouml preserved body begin 00080971
02178 
02179   message.stctOutput.commandNumber = msgType;
02180   message.stctOutput.moduleAddress = DRIVE;
02181   message.stctOutput.typeNumber = 173; //IParameterCurrentControl
02182   message.stctOutput.value = value;
02183 
02184   // Bouml preserved body end 00080971
02185 }
02186 
02187 void IParameterCurrentControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02188                                                    const YouBotJointStorage& storage)
02189 {
02190   // Bouml preserved body begin 000809F1
02191   this->value = (int32)message.stctInput.value;
02192   // Bouml preserved body end 000809F1
02193 }
02194 
02195 DParameterCurrentControl::DParameterCurrentControl()
02196 {
02197   // Bouml preserved body begin 00080B71
02198   this->name = "DParameterCurrentControl";
02199   this->lowerLimit = INT_MIN;
02200   this->upperLimit = INT_MAX;
02201   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02202   // Bouml preserved body end 00080B71
02203 }
02204 
02205 DParameterCurrentControl::~DParameterCurrentControl()
02206 {
02207   // Bouml preserved body begin 00080BF1
02208   // Bouml preserved body end 00080BF1
02209 }
02210 
02211 void DParameterCurrentControl::getParameter(int& parameter) const
02212 {
02213   // Bouml preserved body begin 00080C71
02214   parameter = this->value;
02215   // Bouml preserved body end 00080C71
02216 }
02217 
02218 void DParameterCurrentControl::setParameter(const int parameter)
02219 {
02220   // Bouml preserved body begin 00080CF1
02221   if (this->lowerLimit > parameter)
02222   {
02223     throw std::out_of_range("The parameter exceeds the lower limit");
02224   }
02225   if (this->upperLimit < parameter)
02226   {
02227     throw std::out_of_range("The parameter exceeds the upper limit");
02228   }
02229 
02230   this->value = parameter;
02231   // Bouml preserved body end 00080CF1
02232 }
02233 
02234 void DParameterCurrentControl::toString(std::string& value)
02235 {
02236   // Bouml preserved body begin 0009DB71
02237   std::stringstream ss;
02238   ss << this->name << ": " << this->value;
02239   value = ss.str();
02240   // Bouml preserved body end 0009DB71
02241 }
02242 
02243 void DParameterCurrentControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02244                                                    const YouBotJointStorage& storage) const
02245 {
02246   // Bouml preserved body begin 00080D71
02247 
02248   message.stctOutput.commandNumber = msgType;
02249   message.stctOutput.moduleAddress = DRIVE;
02250   message.stctOutput.typeNumber = 174; //DParameterCurrentControl
02251   message.stctOutput.value = value;
02252 
02253   // Bouml preserved body end 00080D71
02254 }
02255 
02256 void DParameterCurrentControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02257                                                    const YouBotJointStorage& storage)
02258 {
02259   // Bouml preserved body begin 00080DF1
02260   this->value = (int32)message.stctInput.value;
02261   // Bouml preserved body end 00080DF1
02262 }
02263 
02264 IClippingParameterCurrentControl::IClippingParameterCurrentControl()
02265 {
02266   // Bouml preserved body begin 00080F71
02267   this->name = "IClippingParameterCurrentControl";
02268   this->lowerLimit = INT_MIN;
02269   this->upperLimit = INT_MAX;
02270   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02271   // Bouml preserved body end 00080F71
02272 }
02273 
02274 IClippingParameterCurrentControl::~IClippingParameterCurrentControl()
02275 {
02276   // Bouml preserved body begin 00080FF1
02277   // Bouml preserved body end 00080FF1
02278 }
02279 
02280 void IClippingParameterCurrentControl::getParameter(int& parameter) const
02281 {
02282   // Bouml preserved body begin 00081071
02283   parameter = this->value;
02284   // Bouml preserved body end 00081071
02285 }
02286 
02287 void IClippingParameterCurrentControl::setParameter(const int parameter)
02288 {
02289   // Bouml preserved body begin 000810F1
02290   if (this->lowerLimit > parameter)
02291   {
02292     throw std::out_of_range("The parameter exceeds the lower limit");
02293   }
02294   if (this->upperLimit < parameter)
02295   {
02296     throw std::out_of_range("The parameter exceeds the upper limit");
02297   }
02298 
02299   this->value = parameter;
02300   // Bouml preserved body end 000810F1
02301 }
02302 
02303 void IClippingParameterCurrentControl::toString(std::string& value)
02304 {
02305   // Bouml preserved body begin 0009DBF1
02306   std::stringstream ss;
02307   ss << this->name << ": " << this->value;
02308   value = ss.str();
02309   // Bouml preserved body end 0009DBF1
02310 }
02311 
02312 void IClippingParameterCurrentControl::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02313                                                            const YouBotJointStorage& storage) const
02314 {
02315   // Bouml preserved body begin 00081171
02316 
02317   message.stctOutput.commandNumber = msgType;
02318   message.stctOutput.moduleAddress = DRIVE;
02319   message.stctOutput.typeNumber = 175; //IClippingParameterCurrentControl
02320   message.stctOutput.value = value;
02321 
02322   // Bouml preserved body end 00081171
02323 }
02324 
02325 void IClippingParameterCurrentControl::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02326                                                            const YouBotJointStorage& storage)
02327 {
02328   // Bouml preserved body begin 000811F1
02329   this->value = (int32)message.stctInput.value;
02330   // Bouml preserved body end 000811F1
02331 }
02332 
02333 MaximumVelocityToSetPosition::MaximumVelocityToSetPosition()
02334 {
02335   // Bouml preserved body begin 00078F71
02336   this->name = "MaximumVelocityToSetPosition";
02337   this->lowerLimit = INT_MIN * radian_per_second;
02338   this->upperLimit = INT_MAX * radian_per_second;
02339   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02340   // Bouml preserved body end 00078F71
02341 }
02342 
02343 MaximumVelocityToSetPosition::~MaximumVelocityToSetPosition()
02344 {
02345   // Bouml preserved body begin 00078FF1
02346   // Bouml preserved body end 00078FF1
02347 }
02348 
02349 void MaximumVelocityToSetPosition::getParameter(quantity<angular_velocity>& parameter) const
02350 {
02351   // Bouml preserved body begin 00079071
02352   parameter = this->value;
02353   // Bouml preserved body end 00079071
02354 }
02355 
02356 void MaximumVelocityToSetPosition::setParameter(const quantity<angular_velocity>& parameter)
02357 {
02358   // Bouml preserved body begin 000790F1
02359   if (this->lowerLimit > parameter)
02360   {
02361     throw std::out_of_range("The parameter exceeds the lower limit");
02362   }
02363   if (this->upperLimit < parameter)
02364   {
02365     throw std::out_of_range("The parameter exceeds the upper limit");
02366   }
02367 
02368   this->value = parameter;
02369   // Bouml preserved body end 000790F1
02370 }
02371 
02372 void MaximumVelocityToSetPosition::toString(std::string& value)
02373 {
02374   // Bouml preserved body begin 0009CAF1
02375   std::stringstream ss;
02376   ss << this->name << ": " << this->value;
02377   value = ss.str();
02378   // Bouml preserved body end 0009CAF1
02379 }
02380 
02381 void MaximumVelocityToSetPosition::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02382                                                        const YouBotJointStorage& storage) const
02383 {
02384   // Bouml preserved body begin 00079171
02385 
02386   message.stctOutput.commandNumber = msgType;
02387   message.stctOutput.moduleAddress = DRIVE;
02388   message.stctOutput.typeNumber = 7; //MaximumVelocityToSetPosition
02389   message.stctOutput.value = (int32)round((value.value() / (storage.gearRatio * 2.0 * M_PI)) * 60.0);
02390 
02391   // Bouml preserved body end 00079171
02392 }
02393 
02394 void MaximumVelocityToSetPosition::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02395                                                        const YouBotJointStorage& storage)
02396 {
02397   // Bouml preserved body begin 000791F1
02398   double motorRPM = (int32)message.stctInput.value;
02399   this->value = ((motorRPM / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
02400   // Bouml preserved body end 000791F1
02401 }
02402 
02403 PositionTargetReachedDistance::PositionTargetReachedDistance()
02404 {
02405   // Bouml preserved body begin 00079B71
02406   this->name = "PositionTargetReachedDistance";
02407   this->lowerLimit = INT_MIN;
02408   this->upperLimit = INT_MAX;
02409   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02410   // Bouml preserved body end 00079B71
02411 }
02412 
02413 PositionTargetReachedDistance::~PositionTargetReachedDistance()
02414 {
02415   // Bouml preserved body begin 00079BF1
02416   // Bouml preserved body end 00079BF1
02417 }
02418 
02419 void PositionTargetReachedDistance::getParameter(int& parameter) const
02420 {
02421   // Bouml preserved body begin 00079C71
02422   parameter = this->value;
02423   // Bouml preserved body end 00079C71
02424 }
02425 
02426 void PositionTargetReachedDistance::setParameter(const int parameter)
02427 {
02428   // Bouml preserved body begin 00079CF1
02429   if (this->lowerLimit > parameter)
02430   {
02431     throw std::out_of_range("The parameter exceeds the lower limit");
02432   }
02433   if (this->upperLimit < parameter)
02434   {
02435     throw std::out_of_range("The parameter exceeds the upper limit");
02436   }
02437 
02438   this->value = parameter;
02439   // Bouml preserved body end 00079CF1
02440 }
02441 
02442 void PositionTargetReachedDistance::toString(std::string& value)
02443 {
02444   // Bouml preserved body begin 0009CC71
02445   std::stringstream ss;
02446   ss << this->name << ": " << this->value;
02447   value = ss.str();
02448   // Bouml preserved body end 0009CC71
02449 }
02450 
02451 void PositionTargetReachedDistance::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02452                                                         const YouBotJointStorage& storage) const
02453 {
02454   // Bouml preserved body begin 00079D71
02455 
02456   message.stctOutput.commandNumber = msgType;
02457   message.stctOutput.moduleAddress = DRIVE;
02458   message.stctOutput.typeNumber = 10; //PositionTargetReachedDistance
02459   message.stctOutput.value = value;
02460 
02461   // Bouml preserved body end 00079D71
02462 }
02463 
02464 void PositionTargetReachedDistance::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02465                                                         const YouBotJointStorage& storage)
02466 {
02467   // Bouml preserved body begin 00079DF1
02468   this->value = (int32)message.stctInput.value;
02469   // Bouml preserved body end 00079DF1
02470 }
02471 
02472 ClearI2tExceededFlag::ClearI2tExceededFlag()
02473 {
02474   // Bouml preserved body begin 000A15F1
02475   this->name = "ClearI2tExceededFlag";
02476   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02477   this->value = true;
02478   // Bouml preserved body end 000A15F1
02479 }
02480 
02481 ClearI2tExceededFlag::~ClearI2tExceededFlag()
02482 {
02483   // Bouml preserved body begin 000A1671
02484   // Bouml preserved body end 000A1671
02485 }
02486 
02487 void ClearI2tExceededFlag::getParameter() const
02488 {
02489   // Bouml preserved body begin 000A16F1
02490   // Bouml preserved body end 000A16F1
02491 }
02492 
02493 void ClearI2tExceededFlag::setParameter()
02494 {
02495   // Bouml preserved body begin 000A1771
02496   // Bouml preserved body end 000A1771
02497 }
02498 
02499 void ClearI2tExceededFlag::toString(std::string& value)
02500 {
02501   // Bouml preserved body begin 000A17F1
02502   std::stringstream ss;
02503   ss << this->name << ": " << this->value;
02504   value = ss.str();
02505   // Bouml preserved body end 000A17F1
02506 }
02507 
02508 void ClearI2tExceededFlag::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02509                                                const YouBotJointStorage& storage) const
02510 {
02511   // Bouml preserved body begin 000A1871
02512   message.stctOutput.commandNumber = msgType;
02513   message.stctOutput.moduleAddress = DRIVE;
02514   message.stctOutput.typeNumber = 29; //ClearI2tExceededFlag
02515   message.stctOutput.value = value;
02516   // Bouml preserved body end 000A1871
02517 }
02518 
02519 void ClearI2tExceededFlag::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
02520 {
02521   // Bouml preserved body begin 000A18F1
02522   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
02523   {
02524     this->value = message.stctInput.value;
02525   }
02526   // Bouml preserved body end 000A18F1
02527 }
02528 
02529 ClearMotorControllerTimeoutFlag::ClearMotorControllerTimeoutFlag()
02530 {
02531   // Bouml preserved body begin 0009FAF1
02532   this->name = "ClearMotorControllerTimeoutFlag";
02533   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
02534   this->value = true;
02535   // Bouml preserved body end 0009FAF1
02536 }
02537 
02538 ClearMotorControllerTimeoutFlag::~ClearMotorControllerTimeoutFlag()
02539 {
02540   // Bouml preserved body begin 0009FB71
02541   // Bouml preserved body end 0009FB71
02542 }
02543 
02544 bool ClearMotorControllerTimeoutFlag::getParameter() const
02545 {
02546   // Bouml preserved body begin 0009FBF1
02547   return this->value;
02548   // Bouml preserved body end 0009FBF1
02549 }
02550 
02551 void ClearMotorControllerTimeoutFlag::setParameter()
02552 {
02553   // Bouml preserved body begin 0009FC71
02554   // Bouml preserved body end 0009FC71
02555 }
02556 
02557 void ClearMotorControllerTimeoutFlag::toString(std::string& value)
02558 {
02559   // Bouml preserved body begin 0009FCF1
02560   std::stringstream ss;
02561   ss << this->name << ": " << this->value;
02562   value = ss.str();
02563   // Bouml preserved body end 0009FCF1
02564 }
02565 
02566 void ClearMotorControllerTimeoutFlag::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
02567                                                           const YouBotJointStorage& storage) const
02568 {
02569   // Bouml preserved body begin 0009FD71
02570   message.stctOutput.commandNumber = msgType;
02571   message.stctOutput.moduleAddress = DRIVE;
02572   message.stctOutput.typeNumber = 158; //ClearMotorControllerTimeoutFlag
02573   message.stctOutput.value = value;
02574   // Bouml preserved body end 0009FD71
02575 }
02576 
02577 void ClearMotorControllerTimeoutFlag::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
02578                                                           const YouBotJointStorage& storage)
02579 {
02580   // Bouml preserved body begin 0009FDF1
02581   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
02582   {
02583     this->value = message.stctInput.value;
02584   }
02585   // Bouml preserved body end 0009FDF1
02586 }
02587 
02588 PParameterTrajectoryControl::PParameterTrajectoryControl()
02589 {
02590   // Bouml preserved body begin 000ED771
02591   this->name = "PParameterTrajectoryControl";
02592   this->lowerLimit = 0;
02593   this->upperLimit = INT_MAX;
02594   this->parameterType = API_PARAMETER;
02595   // Bouml preserved body end 000ED771
02596 }
02597 
02598 PParameterTrajectoryControl::~PParameterTrajectoryControl()
02599 {
02600   // Bouml preserved body begin 000ED7F1
02601   // Bouml preserved body end 000ED7F1
02602 }
02603 
02604 void PParameterTrajectoryControl::getParameter(double& parameter) const
02605 {
02606   // Bouml preserved body begin 000ED871
02607   parameter = this->value;
02608   // Bouml preserved body end 000ED871
02609 }
02610 
02611 void PParameterTrajectoryControl::setParameter(const double parameter)
02612 {
02613   // Bouml preserved body begin 000ED8F1
02614   if (this->lowerLimit > parameter)
02615   {
02616     throw std::out_of_range("The parameter exceeds the lower limit");
02617   }
02618   if (this->upperLimit < parameter)
02619   {
02620     throw std::out_of_range("The parameter exceeds the upper limit");
02621   }
02622 
02623   this->value = parameter;
02624   // Bouml preserved body end 000ED8F1
02625 }
02626 
02627 void PParameterTrajectoryControl::toString(std::string& value)
02628 {
02629   // Bouml preserved body begin 000ED971
02630   std::stringstream ss;
02631   ss << this->name << ": " << this->value;
02632   value = ss.str();
02633   // Bouml preserved body end 000ED971
02634 }
02635 
02636 IParameterTrajectoryControl::IParameterTrajectoryControl()
02637 {
02638   // Bouml preserved body begin 000EDBF1
02639   this->name = "IParameterTrajectoryControl";
02640   this->lowerLimit = INT_MIN;
02641   this->upperLimit = INT_MAX;
02642   this->parameterType = API_PARAMETER;
02643   // Bouml preserved body end 000EDBF1
02644 }
02645 
02646 IParameterTrajectoryControl::~IParameterTrajectoryControl()
02647 {
02648   // Bouml preserved body begin 000EDC71
02649   // Bouml preserved body end 000EDC71
02650 }
02651 
02652 void IParameterTrajectoryControl::getParameter(double& parameter) const
02653 {
02654   // Bouml preserved body begin 000EDCF1
02655   parameter = this->value;
02656   // Bouml preserved body end 000EDCF1
02657 }
02658 
02659 void IParameterTrajectoryControl::setParameter(const double parameter)
02660 {
02661   // Bouml preserved body begin 000EDD71
02662   if (this->lowerLimit > parameter)
02663   {
02664     throw std::out_of_range("The parameter exceeds the lower limit");
02665   }
02666   if (this->upperLimit < parameter)
02667   {
02668     throw std::out_of_range("The parameter exceeds the upper limit");
02669   }
02670 
02671   this->value = parameter;
02672   // Bouml preserved body end 000EDD71
02673 }
02674 
02675 void IParameterTrajectoryControl::toString(std::string& value)
02676 {
02677   // Bouml preserved body begin 000EDDF1
02678   std::stringstream ss;
02679   ss << this->name << ": " << this->value;
02680   value = ss.str();
02681   // Bouml preserved body end 000EDDF1
02682 }
02683 
02684 DParameterTrajectoryControl::DParameterTrajectoryControl()
02685 {
02686   // Bouml preserved body begin 000EE071
02687   this->name = "DParameterTrajectoryControl";
02688   this->lowerLimit = INT_MIN;
02689   this->upperLimit = INT_MAX;
02690   this->parameterType = API_PARAMETER;
02691   // Bouml preserved body end 000EE071
02692 }
02693 
02694 DParameterTrajectoryControl::~DParameterTrajectoryControl()
02695 {
02696   // Bouml preserved body begin 000EE0F1
02697   // Bouml preserved body end 000EE0F1
02698 }
02699 
02700 void DParameterTrajectoryControl::getParameter(double& parameter) const
02701 {
02702   // Bouml preserved body begin 000EE171
02703   parameter = this->value;
02704   // Bouml preserved body end 000EE171
02705 }
02706 
02707 void DParameterTrajectoryControl::setParameter(const double parameter)
02708 {
02709   // Bouml preserved body begin 000EE1F1
02710   if (this->lowerLimit > parameter)
02711   {
02712     throw std::out_of_range("The parameter exceeds the lower limit");
02713   }
02714   if (this->upperLimit < parameter)
02715   {
02716     throw std::out_of_range("The parameter exceeds the upper limit");
02717   }
02718 
02719   this->value = parameter;
02720   // Bouml preserved body end 000EE1F1
02721 }
02722 
02723 void DParameterTrajectoryControl::toString(std::string& value)
02724 {
02725   // Bouml preserved body begin 000EE271
02726   std::stringstream ss;
02727   ss << this->name << ": " << this->value;
02728   value = ss.str();
02729   // Bouml preserved body end 000EE271
02730 }
02731 
02732 IClippingParameterTrajectoryControl::IClippingParameterTrajectoryControl()
02733 {
02734   // Bouml preserved body begin 000EE4F1
02735   this->name = "IClippingParameterTrajectoryControl";
02736   this->lowerLimit = INT_MIN;
02737   this->upperLimit = INT_MAX;
02738   this->parameterType = API_PARAMETER;
02739   // Bouml preserved body end 000EE4F1
02740 }
02741 
02742 IClippingParameterTrajectoryControl::~IClippingParameterTrajectoryControl()
02743 {
02744   // Bouml preserved body begin 000EE571
02745   // Bouml preserved body end 000EE571
02746 }
02747 
02748 void IClippingParameterTrajectoryControl::getParameter(double& parameter) const
02749 {
02750   // Bouml preserved body begin 000EE5F1
02751   parameter = this->value;
02752   // Bouml preserved body end 000EE5F1
02753 }
02754 
02755 void IClippingParameterTrajectoryControl::setParameter(const double parameter)
02756 {
02757   // Bouml preserved body begin 000EE671
02758   if (this->lowerLimit > parameter)
02759   {
02760     throw std::out_of_range("The parameter exceeds the lower limit");
02761   }
02762   if (this->upperLimit < parameter)
02763   {
02764     throw std::out_of_range("The parameter exceeds the upper limit");
02765   }
02766 
02767   this->value = parameter;
02768   // Bouml preserved body end 000EE671
02769 }
02770 
02771 void IClippingParameterTrajectoryControl::toString(std::string& value)
02772 {
02773   // Bouml preserved body begin 000EE6F1
02774   std::stringstream ss;
02775   ss << this->name << ": " << this->value;
02776   value = ss.str();
02777   // Bouml preserved body end 000EE6F1
02778 }
02779 
02780 } // namespace youbot


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