YouBotJointParameterReadOnly.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/YouBotJointParameterReadOnly.hpp>
00052 namespace youbot
00053 {
00054 
00055 YouBotJointParameterReadOnly::YouBotJointParameterReadOnly()
00056 {
00057   // Bouml preserved body begin 0006FDF1
00058   // Bouml preserved body end 0006FDF1
00059 }
00060 
00061 YouBotJointParameterReadOnly::~YouBotJointParameterReadOnly()
00062 {
00063   // Bouml preserved body begin 0006FE71
00064   // Bouml preserved body end 0006FE71
00065 }
00066 
00067 ActualMotorVoltage::ActualMotorVoltage()
00068 {
00069   // Bouml preserved body begin 0007E071
00070   this->name = "ActualMotorVoltage";
00071   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00072   // Bouml preserved body end 0007E071
00073 }
00074 
00075 ActualMotorVoltage::~ActualMotorVoltage()
00076 {
00077   // Bouml preserved body begin 0007E0F1
00078   // Bouml preserved body end 0007E0F1
00079 }
00080 
00081 void ActualMotorVoltage::getParameter(quantity<electric_potential>& parameter) const
00082 {
00083   // Bouml preserved body begin 0007E171
00084   parameter = this->value;
00085   // Bouml preserved body end 0007E171
00086 }
00087 
00088 void ActualMotorVoltage::toString(std::string& value)
00089 {
00090   // Bouml preserved body begin 0009EC71
00091   std::stringstream ss;
00092   ss << this->name << ": " << this->value;
00093   value = ss.str();
00094   // Bouml preserved body end 0009EC71
00095 }
00096 
00097 void ActualMotorVoltage::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00098                                              const YouBotJointStorage& storage) const
00099 {
00100   // Bouml preserved body begin 0007E1F1
00101   message.stctOutput.commandNumber = msgType;
00102   message.stctOutput.moduleAddress = DRIVE;
00103   message.stctOutput.typeNumber = 151; //ActualMotorVoltage
00104   //  message.stctOutput.value = value;
00105 
00106   // Bouml preserved body end 0007E1F1
00107 }
00108 
00109 void ActualMotorVoltage::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00110 {
00111   // Bouml preserved body begin 0007E271
00112   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00113   {
00114     double temp = message.stctInput.value;
00115     this->value = temp / 100.0 * volt; //TODO do convertion
00116   }
00117   // Bouml preserved body end 0007E271
00118 }
00119 
00120 ErrorAndStatus::ErrorAndStatus()
00121 {
00122   // Bouml preserved body begin 0007E771
00123   this->name = "ErrorAndStatus";
00124   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00125   // Bouml preserved body end 0007E771
00126 }
00127 
00128 ErrorAndStatus::~ErrorAndStatus()
00129 {
00130   // Bouml preserved body begin 0007E7F1
00131   // Bouml preserved body end 0007E7F1
00132 }
00133 
00134 void ErrorAndStatus::getParameter(unsigned int& parameter) const
00135 {
00136   // Bouml preserved body begin 0007E871
00137   parameter = this->value;
00138   this->parseYouBotErrorFlags();
00139   // Bouml preserved body end 0007E871
00140 }
00141 
00142 void ErrorAndStatus::toString(std::string& value)
00143 {
00144   // Bouml preserved body begin 0009ED71
00145   std::stringstream ss;
00146   ss << this->name << ": " << this->value;
00147   value = ss.str();
00148   // Bouml preserved body end 0009ED71
00149 }
00150 
00151 void ErrorAndStatus::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00152                                          const YouBotJointStorage& storage) const
00153 {
00154   // Bouml preserved body begin 0007E8F1
00155   message.stctOutput.commandNumber = msgType;
00156   message.stctOutput.moduleAddress = DRIVE;
00157   message.stctOutput.typeNumber = 156; //ErrorAndStatus
00158   //   message.stctOutput.value = value;
00159 
00160   // Bouml preserved body end 0007E8F1
00161 }
00162 
00163 void ErrorAndStatus::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00164 {
00165   // Bouml preserved body begin 0007E971
00166   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00167   {
00168     this->value = message.stctInput.value;
00169   }
00170   // Bouml preserved body end 0007E971
00171 }
00172 
00173 void ErrorAndStatus::parseYouBotErrorFlags() const
00174 {
00175   // Bouml preserved body begin 0007EAF1
00176   // std::stringstream errorMessageStream;
00177   // errorMessageStream << "Joint " << this->jointNumber << " ";
00178   std::string errorMessage;
00179   // errorMessage = errorMessageStream.str();
00180 
00181   if (value & OVER_CURRENT)
00182   {
00183     LOG(warning) << errorMessage << "over current";
00184     //    throw JointErrorException(errorMessage + "got over current");
00185   }
00186 
00187   if (value & UNDER_VOLTAGE)
00188   {
00189     LOG(warning) << errorMessage << "under voltage";
00190     //    throw JointErrorException(errorMessage + "got under voltage");
00191   }
00192 
00193   if (value & OVER_VOLTAGE)
00194   {
00195     LOG(warning) << errorMessage << "over voltage";
00196     //   throw JointErrorException(errorMessage + "got over voltage");
00197   }
00198 
00199   if (value & OVER_TEMPERATURE)
00200   {
00201     LOG(warning) << errorMessage << "over temperature";
00202     //   throw JointErrorException(errorMessage + "got over temperature");
00203   }
00204 
00205   if (value & MOTOR_HALTED)
00206   {
00207     LOG(info) << errorMessage << "is halted";
00208     //   throw JointErrorException(errorMessage + "is halted");
00209   }
00210 
00211   if (value & HALL_SENSOR_ERROR)
00212   {
00213     LOG(warning) << errorMessage << "hall sensor problem";
00214     //   throw JointErrorException(errorMessage + "got hall sensor problem");
00215   }
00216 
00217 //    if (value & PWM_MODE_ACTIVE) {
00218 //      LOG(info) << errorMessage << "PWM mode active";
00219   //   throw JointErrorException(errorMessage + "the cycle time is violated");
00220 //    }
00221 
00222   if (value & VELOCITY_MODE)
00223   {
00224     LOG(info) << errorMessage << "velocity mode active";
00225     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00226   }
00227 
00228   if (value & POSITION_MODE)
00229   {
00230     LOG(info) << errorMessage << "position mode active";
00231     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00232   }
00233 
00234   if (value & TORQUE_MODE)
00235   {
00236     LOG(info) << errorMessage << "torque mode active";
00237     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00238   }
00239 
00240   if (value & POSITION_REACHED)
00241   {
00242     LOG(info) << errorMessage << "position reached";
00243     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00244   }
00245 
00246   if (value & INITIALIZED)
00247   {
00248     LOG(info) << errorMessage << "is initialized";
00249     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00250   }
00251 
00252   if (value & TIMEOUT)
00253   {
00254     LOG(warning) << errorMessage << "timeout";
00255     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00256   }
00257 
00258   if (value & I2T_EXCEEDED)
00259   {
00260     LOG(warning) << errorMessage << "I2t exceeded";
00261     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00262   }
00263 
00264   // Bouml preserved body end 0007EAF1
00265 }
00266 
00267 PositionError::PositionError()
00268 {
00269   // Bouml preserved body begin 00081771
00270   this->name = "PositionError";
00271   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00272   // Bouml preserved body end 00081771
00273 }
00274 
00275 PositionError::~PositionError()
00276 {
00277   // Bouml preserved body begin 000817F1
00278   // Bouml preserved body end 000817F1
00279 }
00280 
00281 void PositionError::getParameter(quantity<plane_angle>& parameter) const
00282 {
00283   // Bouml preserved body begin 00081871
00284   parameter = this->value;
00285   // Bouml preserved body end 00081871
00286 }
00287 
00288 void PositionError::toString(std::string& value)
00289 {
00290   // Bouml preserved body begin 0009EDF1
00291   std::stringstream ss;
00292   ss << this->name << ": " << this->value;
00293   value = ss.str();
00294   // Bouml preserved body end 0009EDF1
00295 }
00296 
00297 void PositionError::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00298                                         const YouBotJointStorage& storage) const
00299 {
00300   // Bouml preserved body begin 00081971
00301   message.stctOutput.commandNumber = msgType;
00302   message.stctOutput.moduleAddress = DRIVE;
00303   message.stctOutput.typeNumber = 226; //PositionError
00304 //    message.stctOutput.value = value;
00305       // Bouml preserved body end 00081971
00306 }
00307 
00308 void PositionError::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00309 {
00310   // Bouml preserved body begin 000819F1
00311   double temp = (int)message.stctInput.value;
00312   value = (temp / storage.encoderTicksPerRound) * storage.gearRatio * (2.0 * M_PI) * radian;
00313   // Bouml preserved body end 000819F1
00314 }
00315 
00316 PositionErrorSum::PositionErrorSum()
00317 {
00318   // Bouml preserved body begin 00081B71
00319   this->name = "PositionErrorSum";
00320   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00321   // Bouml preserved body end 00081B71
00322 }
00323 
00324 PositionErrorSum::~PositionErrorSum()
00325 {
00326   // Bouml preserved body begin 00081BF1
00327   // Bouml preserved body end 00081BF1
00328 }
00329 
00330 void PositionErrorSum::getParameter(quantity<plane_angle>& parameter) const
00331 {
00332   // Bouml preserved body begin 00081C71
00333   parameter = this->value;
00334   // Bouml preserved body end 00081C71
00335 }
00336 
00337 void PositionErrorSum::toString(std::string& value)
00338 {
00339   // Bouml preserved body begin 0009EE71
00340   std::stringstream ss;
00341   ss << this->name << ": " << this->value;
00342   value = ss.str();
00343   // Bouml preserved body end 0009EE71
00344 }
00345 
00346 void PositionErrorSum::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00347                                            const YouBotJointStorage& storage) const
00348 {
00349   // Bouml preserved body begin 00081D71
00350 
00351   message.stctOutput.commandNumber = msgType;
00352   message.stctOutput.moduleAddress = DRIVE;
00353   message.stctOutput.typeNumber = 227; //PositionErrorSum
00354   //   message.stctOutput.value = value;
00355 
00356   // Bouml preserved body end 00081D71
00357 }
00358 
00359 void PositionErrorSum::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00360 {
00361   // Bouml preserved body begin 00081DF1
00362   double temp = (int)message.stctInput.value;
00363   value = (temp / storage.encoderTicksPerRound) * storage.gearRatio * (2.0 * M_PI) * radian;
00364   // Bouml preserved body end 00081DF1
00365 }
00366 
00367 VelocityError::VelocityError()
00368 {
00369   // Bouml preserved body begin 00081F71
00370   this->name = "VelocityError";
00371   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00372   // Bouml preserved body end 00081F71
00373 }
00374 
00375 VelocityError::~VelocityError()
00376 {
00377   // Bouml preserved body begin 00081FF1
00378   // Bouml preserved body end 00081FF1
00379 }
00380 
00381 void VelocityError::getParameter(quantity<si::angular_velocity>& parameter) const
00382 {
00383   // Bouml preserved body begin 00082071
00384   parameter = this->value;
00385   // Bouml preserved body end 00082071
00386 }
00387 
00388 void VelocityError::toString(std::string& value)
00389 {
00390   // Bouml preserved body begin 0009EEF1
00391   std::stringstream ss;
00392   ss << this->name << ": " << this->value;
00393   value = ss.str();
00394   // Bouml preserved body end 0009EEF1
00395 }
00396 
00397 void VelocityError::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00398                                         const YouBotJointStorage& storage) const
00399 {
00400   // Bouml preserved body begin 00082171
00401 
00402   message.stctOutput.commandNumber = msgType;
00403   message.stctOutput.moduleAddress = DRIVE;
00404   message.stctOutput.typeNumber = 228; //VelocityError
00405   //   message.stctOutput.value = value;
00406 
00407   // Bouml preserved body end 00082171
00408 }
00409 
00410 void VelocityError::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00411 {
00412   // Bouml preserved body begin 000821F1
00413   double temp = (int)message.stctInput.value;
00414   this->value = ((temp / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00415   // Bouml preserved body end 000821F1
00416 }
00417 
00418 VelocityErrorSum::VelocityErrorSum()
00419 {
00420   // Bouml preserved body begin 00082371
00421   this->name = "VelocityErrorSum";
00422   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00423   // Bouml preserved body end 00082371
00424 }
00425 
00426 VelocityErrorSum::~VelocityErrorSum()
00427 {
00428   // Bouml preserved body begin 000823F1
00429   // Bouml preserved body end 000823F1
00430 }
00431 
00432 void VelocityErrorSum::getParameter(quantity<si::angular_velocity>& parameter) const
00433 {
00434   // Bouml preserved body begin 00082471
00435   parameter = this->value;
00436   // Bouml preserved body end 00082471
00437 }
00438 
00439 void VelocityErrorSum::toString(std::string& value)
00440 {
00441   // Bouml preserved body begin 0009EF71
00442   std::stringstream ss;
00443   ss << this->name << ": " << this->value;
00444   value = ss.str();
00445   // Bouml preserved body end 0009EF71
00446 }
00447 
00448 void VelocityErrorSum::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00449                                            const YouBotJointStorage& storage) const
00450 {
00451   // Bouml preserved body begin 00082571
00452 
00453   message.stctOutput.commandNumber = msgType;
00454   message.stctOutput.moduleAddress = DRIVE;
00455   message.stctOutput.typeNumber = 229; //VelocityErrorSum
00456   //   message.stctOutput.value = value;
00457 
00458   // Bouml preserved body end 00082571
00459 }
00460 
00461 void VelocityErrorSum::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00462 {
00463   // Bouml preserved body begin 000825F1
00464   double temp = (int32)message.stctInput.value;
00465   this->value = ((temp / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00466 
00467   // Bouml preserved body end 000825F1
00468 }
00469 
00470 CurrentError::CurrentError()
00471 {
00472   // Bouml preserved body begin 000DAEF1
00473   this->name = "CurrentError";
00474   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00475   // Bouml preserved body end 000DAEF1
00476 }
00477 
00478 CurrentError::~CurrentError()
00479 {
00480   // Bouml preserved body begin 000DAF71
00481   // Bouml preserved body end 000DAF71
00482 }
00483 
00484 void CurrentError::getParameter(quantity<si::current>& parameter) const
00485 {
00486   // Bouml preserved body begin 000DAFF1
00487   parameter = this->value;
00488   // Bouml preserved body end 000DAFF1
00489 }
00490 
00491 void CurrentError::toString(std::string& value)
00492 {
00493   // Bouml preserved body begin 000DB071
00494   std::stringstream ss;
00495   ss << this->name << ": " << this->value;
00496   value = ss.str();
00497   // Bouml preserved body end 000DB071
00498 }
00499 
00500 void CurrentError::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00501                                        const YouBotJointStorage& storage) const
00502 {
00503   // Bouml preserved body begin 000DB0F1
00504   message.stctOutput.commandNumber = msgType;
00505   message.stctOutput.moduleAddress = DRIVE;
00506   message.stctOutput.typeNumber = 200; //CurrentError
00507   //  message.stctOutput.value = value;
00508 
00509   // Bouml preserved body end 000DB0F1
00510 }
00511 
00512 void CurrentError::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00513 {
00514   // Bouml preserved body begin 000DB171
00515   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00516   {
00517     double temp = (int)message.stctInput.value;
00518     this->value = temp / 1000.0 * ampere; //convert from milli A to A
00519   }
00520   // Bouml preserved body end 000DB171
00521 }
00522 
00523 CurrentErrorSum::CurrentErrorSum()
00524 {
00525   // Bouml preserved body begin 000DB2F1
00526   this->name = "CurrentErrorSum";
00527   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00528   // Bouml preserved body end 000DB2F1
00529 }
00530 
00531 CurrentErrorSum::~CurrentErrorSum()
00532 {
00533   // Bouml preserved body begin 000DB371
00534   // Bouml preserved body end 000DB371
00535 }
00536 
00537 void CurrentErrorSum::getParameter(quantity<si::current>& parameter) const
00538 {
00539   // Bouml preserved body begin 000DB3F1
00540   parameter = this->value;
00541   // Bouml preserved body end 000DB3F1
00542 }
00543 
00544 void CurrentErrorSum::toString(std::string& value)
00545 {
00546   // Bouml preserved body begin 000DB471
00547   std::stringstream ss;
00548   ss << this->name << ": " << this->value;
00549   value = ss.str();
00550   // Bouml preserved body end 000DB471
00551 }
00552 
00553 void CurrentErrorSum::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00554                                           const YouBotJointStorage& storage) const
00555 {
00556   // Bouml preserved body begin 000DB4F1
00557   message.stctOutput.commandNumber = msgType;
00558   message.stctOutput.moduleAddress = DRIVE;
00559   message.stctOutput.typeNumber = 201; //CurrentErrorSum
00560   //  message.stctOutput.value = value;
00561 
00562   // Bouml preserved body end 000DB4F1
00563 }
00564 
00565 void CurrentErrorSum::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00566 {
00567   // Bouml preserved body begin 000DB571
00568   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00569   {
00570     double temp = (int)message.stctInput.value;
00571     this->value = temp / 1000.0 * ampere; //convert from milli A to A
00572   }
00573   // Bouml preserved body end 000DB571
00574 }
00575 
00576 RampGeneratorSpeed::RampGeneratorSpeed()
00577 {
00578   // Bouml preserved body begin 0009F271
00579   this->name = "RampGeneratorSpeed";
00580   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00581   // Bouml preserved body end 0009F271
00582 }
00583 
00584 RampGeneratorSpeed::~RampGeneratorSpeed()
00585 {
00586   // Bouml preserved body begin 0009F2F1
00587   // Bouml preserved body end 0009F2F1
00588 }
00589 
00590 void RampGeneratorSpeed::getParameter(quantity<si::angular_velocity>& parameter) const
00591 {
00592   // Bouml preserved body begin 0009F371
00593   parameter = this->value;
00594   // Bouml preserved body end 0009F371
00595 }
00596 
00597 void RampGeneratorSpeed::toString(std::string& value)
00598 {
00599   // Bouml preserved body begin 0009F3F1
00600   std::stringstream ss;
00601   ss << this->name << ": " << this->value;
00602   value = ss.str();
00603   // Bouml preserved body end 0009F3F1
00604 }
00605 
00606 void RampGeneratorSpeed::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00607                                              const YouBotJointStorage& storage) const
00608 {
00609   // Bouml preserved body begin 0009F471
00610 
00611   message.stctOutput.commandNumber = msgType;
00612   message.stctOutput.moduleAddress = DRIVE;
00613   message.stctOutput.typeNumber = 13; //RampGeneratorSpeed
00614   //   message.stctOutput.value = value;
00615 
00616   // Bouml preserved body end 0009F471
00617 }
00618 
00619 void RampGeneratorSpeed::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00620 {
00621   // Bouml preserved body begin 0009F4F1
00622   double temp = (int)message.stctInput.value;
00623   this->value = ((temp / 60.0) * storage.gearRatio * 2.0 * M_PI) * radian_per_second;
00624   // Bouml preserved body end 0009F4F1
00625 }
00626 
00627 I2tSum::I2tSum()
00628 {
00629   // Bouml preserved body begin 000A0CF1
00630   this->name = "I2tSum";
00631   this->lowerLimit = 0;
00632   this->upperLimit = INT_MAX;
00633   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00634   // Bouml preserved body end 000A0CF1
00635 }
00636 
00637 I2tSum::~I2tSum()
00638 {
00639   // Bouml preserved body begin 000A0D71
00640   // Bouml preserved body end 000A0D71
00641 }
00642 
00643 void I2tSum::getParameter(unsigned int& parameter) const
00644 {
00645   // Bouml preserved body begin 000A0DF1
00646   parameter = this->value;
00647   // Bouml preserved body end 000A0DF1
00648 }
00649 
00650 void I2tSum::setParameter(const unsigned int parameter)
00651 {
00652   // Bouml preserved body begin 000A0E71
00653   if (this->lowerLimit > parameter)
00654   {
00655     throw std::out_of_range("The parameter exceeds the lower limit");
00656   }
00657   if (this->upperLimit < parameter)
00658   {
00659     throw std::out_of_range("The parameter exceeds the upper limit");
00660   }
00661   this->value = parameter;
00662   // Bouml preserved body end 000A0E71
00663 }
00664 
00665 void I2tSum::toString(std::string& value)
00666 {
00667   // Bouml preserved body begin 000A0EF1
00668   std::stringstream ss;
00669   ss << this->name << ": " << this->value;
00670   value = ss.str();
00671   // Bouml preserved body end 000A0EF1
00672 }
00673 
00674 void I2tSum::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00675                                  const YouBotJointStorage& storage) const
00676 {
00677   // Bouml preserved body begin 000A0F71
00678   message.stctOutput.commandNumber = msgType;
00679   message.stctOutput.moduleAddress = DRIVE;
00680   message.stctOutput.typeNumber = 27; //I2tSum
00681   message.stctOutput.value = value;
00682   // Bouml preserved body end 000A0F71
00683 }
00684 
00685 void I2tSum::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00686 {
00687   // Bouml preserved body begin 000A0FF1
00688   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00689   {
00690     this->value = message.stctInput.value;
00691   }
00692   // Bouml preserved body end 000A0FF1
00693 }
00694 
00695 ActualMotorDriverTemperature::ActualMotorDriverTemperature()
00696 {
00697   // Bouml preserved body begin 000CB071
00698   this->name = "ActualMotorDriverTemperature";
00699   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00700   // Bouml preserved body end 000CB071
00701 }
00702 
00703 ActualMotorDriverTemperature::~ActualMotorDriverTemperature()
00704 {
00705   // Bouml preserved body begin 000CB0F1
00706   // Bouml preserved body end 000CB0F1
00707 }
00708 
00709 void ActualMotorDriverTemperature::getParameter(quantity<celsius::temperature>& parameter) const
00710 {
00711   // Bouml preserved body begin 000CB171
00712   parameter = this->value;
00713   // Bouml preserved body end 000CB171
00714 }
00715 
00716 void ActualMotorDriverTemperature::toString(std::string& value)
00717 {
00718   // Bouml preserved body begin 000CB1F1
00719   std::stringstream ss;
00720   ss << this->name << ": " << this->value;
00721   value = ss.str();
00722   // Bouml preserved body end 000CB1F1
00723 }
00724 
00725 void ActualMotorDriverTemperature::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00726                                                        const YouBotJointStorage& storage) const
00727 {
00728   // Bouml preserved body begin 000CB271
00729   message.stctOutput.commandNumber = msgType;
00730   message.stctOutput.moduleAddress = DRIVE;
00731   message.stctOutput.typeNumber = 152; //ActualMotorDriverTemperature
00732   //  message.stctOutput.value = value;
00733 
00734   // Bouml preserved body end 000CB271
00735 }
00736 
00737 void ActualMotorDriverTemperature::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00738                                                        const YouBotJointStorage& storage)
00739 {
00740   // Bouml preserved body begin 000CB2F1
00741   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00742   {
00743     double materialConstant = 3434;
00744     double R_NTC = ((double)9011.2 / message.stctInput.value) - 2.2;
00745     double nominator = materialConstant * 298.16;
00746     double denominator = materialConstant + (log(R_NTC / 10.0) * 298.16);
00747     this->value = ((nominator / denominator) - 273.16) * celsius::degree;
00748   }
00749   // Bouml preserved body end 000CB2F1
00750 }
00751 
00752 ActualModuleSupplyCurrent::ActualModuleSupplyCurrent()
00753 {
00754   // Bouml preserved body begin 000CB471
00755   this->name = "ActualModuleSupplyCurrent";
00756   this->parameterType = MOTOR_CONTOLLER_PARAMETER;
00757   // Bouml preserved body end 000CB471
00758 }
00759 
00760 ActualModuleSupplyCurrent::~ActualModuleSupplyCurrent()
00761 {
00762   // Bouml preserved body begin 000CB4F1
00763   // Bouml preserved body end 000CB4F1
00764 }
00765 
00766 void ActualModuleSupplyCurrent::getParameter(quantity<si::current>& parameter) const
00767 {
00768   // Bouml preserved body begin 000CB571
00769   parameter = this->value;
00770   // Bouml preserved body end 000CB571
00771 }
00772 
00773 void ActualModuleSupplyCurrent::toString(std::string& value)
00774 {
00775   // Bouml preserved body begin 000CB5F1
00776   std::stringstream ss;
00777   ss << this->name << ": " << this->value;
00778   value = ss.str();
00779   // Bouml preserved body end 000CB5F1
00780 }
00781 
00782 void ActualModuleSupplyCurrent::getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00783                                                     const YouBotJointStorage& storage) const
00784 {
00785   // Bouml preserved body begin 000CB671
00786   message.stctOutput.commandNumber = msgType;
00787   message.stctOutput.moduleAddress = DRIVE;
00788   message.stctOutput.typeNumber = 157; //ActualModuleSupplyCurrent
00789   //  message.stctOutput.value = value;
00790 
00791   // Bouml preserved body end 000CB671
00792 }
00793 
00794 void ActualModuleSupplyCurrent::setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message,
00795                                                     const YouBotJointStorage& storage)
00796 {
00797   // Bouml preserved body begin 000CB6F1
00798   if (message.stctOutput.commandNumber == message.stctInput.commandNumber && message.stctInput.status == NO_ERROR)
00799   {
00800     this->value = (double)message.stctInput.value / 1000.0 * ampere; //convert from milli A to A
00801   }
00802   // Bouml preserved body end 000CB6F1
00803 }
00804 
00805 } // namespace youbot


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