YouBotJointParameter.hpp
Go to the documentation of this file.
00001 #ifndef YOUBOT_YOUBOTJOINTPARAMETER_H
00002 #define YOUBOT_YOUBOTJOINTPARAMETER_H
00003 
00004 /****************************************************************
00005  *
00006  * Copyright (c) 2011
00007  * All rights reserved.
00008  *
00009  * Hochschule Bonn-Rhein-Sieg
00010  * University of Applied Sciences
00011  * Computer Science Department
00012  *
00013  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00014  *
00015  * Author:
00016  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
00017  * Supervised by:
00018  * Gerhard K. Kraetzschmar
00019  *
00020  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00021  *
00022  * This sofware is published under a dual-license: GNU Lesser General Public 
00023  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
00024  * code may choose which terms they prefer.
00025  *
00026  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00027  *
00028  * Redistribution and use in source and binary forms, with or without
00029  * modification, are permitted provided that the following conditions are met:
00030  *
00031  *     * Redistributions of source code must retain the above copyright
00032  *       notice, this list of conditions and the following disclaimer.
00033  *     * Redistributions in binary form must reproduce the above copyright
00034  *       notice, this list of conditions and the following disclaimer in the
00035  *       documentation and/or other materials provided with the distribution.
00036  *     * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
00037  *       contributors may be used to endorse or promote products derived from
00038  *       this software without specific prior written permission.
00039  *
00040  * This program is free software: you can redistribute it and/or modify
00041  * it under the terms of the GNU Lesser General Public License LGPL as
00042  * published by the Free Software Foundation, either version 2.1 of the
00043  * License, or (at your option) any later version or the BSD license.
00044  *
00045  * This program is distributed in the hope that it will be useful,
00046  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00047  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00048  * GNU Lesser General Public License LGPL and the BSD license for more details.
00049  *
00050  * You should have received a copy of the GNU Lesser General Public
00051  * License LGPL and BSD license along with this program.
00052  *
00053  ****************************************************************/
00054 #include <vector>
00055 #include <sstream>
00056 #include <boost/limits.hpp>
00057 #include <youbot_driver/generic/Logger.hpp>
00058 #include <youbot_driver/generic/Units.hpp>
00059 #include <youbot_driver/generic/Time.hpp>
00060 #include <youbot_driver/generic/Exceptions.hpp>
00061 #include <youbot_driver/generic-joint/JointParameter.hpp>
00062 #include <youbot_driver/youbot/YouBotJointParameterReadOnly.hpp>
00063 #include <youbot_driver/youbot/ProtocolDefinitions.hpp>
00064 #include <youbot_driver/youbot/YouBotSlaveMsg.hpp>
00065 #include <youbot_driver/youbot/YouBotSlaveMailboxMsg.hpp>
00066 #include <youbot_driver/youbot/YouBotJointStorage.hpp>
00067 namespace youbot
00068 {
00069 
00070 enum CalibrationDirection
00071 {
00072   POSITIV, NEGATIV
00073 
00074 };
00078 class YouBotApiJointParameter : public JointParameter
00079 {
00080   friend class YouBotJoint;
00081 protected:
00082   YouBotApiJointParameter();
00083 
00084 public:
00085   virtual ~YouBotApiJointParameter();
00086 
00087   virtual void toString(std::string& value) = 0;
00088 
00089 protected:
00090   virtual void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00091                                    const YouBotJointStorage& storage) const = 0;
00092 
00093   virtual void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage) = 0;
00094 
00095   virtual std::string getName() const = 0;
00096 
00097   virtual ParameterType getType() const = 0;
00098 
00099   std::string name;
00100 
00101   ParameterType parameterType;
00102 
00103 };
00107 class YouBotJointParameter : public YouBotJointParameterReadOnly
00108 {
00109   friend class YouBotJoint;
00110 protected:
00111   YouBotJointParameter();
00112 
00113 public:
00114   virtual ~YouBotJointParameter();
00115 
00116   virtual void toString(std::string& value) = 0;
00117 
00118 protected:
00119   virtual void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00120                                    const YouBotJointStorage& storage) const = 0;
00121 
00122   virtual void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage) = 0;
00123 
00124   virtual std::string getName() const = 0;
00125 
00126   virtual ParameterType getType() const = 0;
00127 
00128   std::string name;
00129 
00130   ParameterType parameterType;
00131 
00132 };
00136 class JointName : public YouBotApiJointParameter
00137 {
00138   friend class YouBotJoint;
00139 public:
00140   JointName();
00141 
00142   virtual ~JointName();
00143 
00144   void getParameter(std::string& parameter) const;
00145 
00146   void setParameter(const std::string parameter);
00147 
00148   void toString(std::string& value);
00149 
00150 private:
00151   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00152                            const YouBotJointStorage& storage) const
00153   {
00154   }
00155   ;
00156 
00157   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00158   {
00159   }
00160   ;
00161 
00162   std::string getName() const
00163   {
00164     return this->name;
00165   }
00166   ;
00167 
00168   ParameterType getType() const
00169   {
00170     return this->parameterType;
00171   }
00172   ;
00173 
00174   std::string value;
00175 
00176   std::string name;
00177 
00178   ParameterType parameterType;
00179 
00180 };
00184 class InitializeJoint : public YouBotJointParameter
00185 {
00186   friend class YouBotJoint;
00187 public:
00188   InitializeJoint();
00189 
00190   virtual ~InitializeJoint();
00191 
00192   void getParameter(bool& parameter) const;
00193 
00194   void setParameter(const bool parameter);
00195 
00196   void toString(std::string& value);
00197 
00198 private:
00199   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00200                            const YouBotJointStorage& storage) const;
00201 
00202   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00203 
00204   std::string getName() const
00205   {
00206     return this->name;
00207   }
00208   ;
00209 
00210   ParameterType getType() const
00211   {
00212     return this->parameterType;
00213   }
00214   ;
00215 
00216   bool value;
00217 
00218   std::string name;
00219 
00220   ParameterType parameterType;
00221 
00222 };
00226 class CalibrateJoint : public YouBotApiJointParameter
00227 {
00228   friend class YouBotJoint;
00229 public:
00230   CalibrateJoint();
00231 
00232   virtual ~CalibrateJoint();
00233 
00234   void getParameter(bool& doCalibration, CalibrationDirection& calibrationDirection,
00235                     quantity<si::current>& maxCurrent) const;
00236 
00237   void setParameter(const bool doCalibration, CalibrationDirection calibrationDirection,
00238                     const quantity<si::current>& maxCurrent);
00239 
00240   void toString(std::string& value);
00241 
00242 private:
00243   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00244                            const YouBotJointStorage& storage) const
00245   {
00246   }
00247   ;
00248 
00249   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00250   {
00251   }
00252   ;
00253 
00254   std::string getName() const
00255   {
00256     return this->name;
00257   }
00258   ;
00259 
00260   ParameterType getType() const
00261   {
00262     return this->parameterType;
00263   }
00264   ;
00265 
00266   bool doCalibration;
00267 
00268   std::string name;
00269 
00270   ParameterType parameterType;
00271 
00272   CalibrationDirection calibrationDirection;
00273 
00274   quantity<si::current> maxCurrent;
00275 
00276 };
00280 class FirmwareVersion : public YouBotApiJointParameter
00281 {
00282   friend class YouBotJoint;
00283 public:
00284   FirmwareVersion();
00285 
00286   virtual ~FirmwareVersion();
00287 
00288   void getParameter(int& controllerType, std::string& firmwareVersion) const;
00289 
00290   void setParameter(const int controllerType, const std::string firmwareVersion);
00291 
00292   void toString(std::string& value);
00293 
00294 private:
00295   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00296                            const YouBotJointStorage& storage) const;
00297 
00298   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00299 
00300   std::string getName() const
00301   {
00302     return this->name;
00303   }
00304   ;
00305 
00306   ParameterType getType() const
00307   {
00308     return this->parameterType;
00309   }
00310   ;
00311 
00312   int controllerType;
00313 
00314   std::string firmwareVersion;
00315 
00316   std::string name;
00317 
00318   ParameterType parameterType;
00319 
00320 };
00324 class GearRatio : public YouBotApiJointParameter
00325 {
00326   friend class YouBotJoint;
00327 public:
00328   GearRatio();
00329 
00330   virtual ~GearRatio();
00331 
00332   void getParameter(double& parameter) const;
00333 
00334   void setParameter(const double parameter);
00335 
00336   void toString(std::string& value);
00337 
00338 private:
00339   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00340                            const YouBotJointStorage& storage) const
00341   {
00342   }
00343   ;
00344 
00345   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00346   {
00347   }
00348   ;
00349 
00350   std::string getName() const
00351   {
00352     return this->name;
00353   }
00354   ;
00355 
00356   ParameterType getType() const
00357   {
00358     return this->parameterType;
00359   }
00360   ;
00361 
00362   double value;
00363 
00364   std::string name;
00365 
00366   ParameterType parameterType;
00367 
00368 };
00372 class EncoderTicksPerRound : public YouBotApiJointParameter
00373 {
00374   friend class YouBotJoint;
00375 public:
00376   EncoderTicksPerRound();
00377 
00378   virtual ~EncoderTicksPerRound();
00379 
00380   void getParameter(unsigned int& parameter) const;
00381 
00382   void setParameter(const unsigned int parameter);
00383 
00384   void toString(std::string& value);
00385 
00386 private:
00387   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00388                            const YouBotJointStorage& storage) const
00389   {
00390   }
00391   ;
00392 
00393   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00394   {
00395   }
00396   ;
00397 
00398   std::string getName() const
00399   {
00400     return this->name;
00401   }
00402   ;
00403 
00404   ParameterType getType() const
00405   {
00406     return this->parameterType;
00407   }
00408   ;
00409 
00410   unsigned int value;
00411 
00412   std::string name;
00413 
00414   ParameterType parameterType;
00415 
00416 };
00420 class InverseMovementDirection : public YouBotApiJointParameter
00421 {
00422   friend class YouBotJoint;
00423 public:
00424   InverseMovementDirection();
00425 
00426   virtual ~InverseMovementDirection();
00427 
00428   void getParameter(bool& parameter) const;
00429 
00430   void setParameter(const bool parameter);
00431 
00432   void toString(std::string& value);
00433 
00434 private:
00435   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00436                            const YouBotJointStorage& storage) const
00437   {
00438   }
00439   ;
00440 
00441   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00442   {
00443   }
00444   ;
00445 
00446   std::string getName() const
00447   {
00448     return this->name;
00449   }
00450   ;
00451 
00452   ParameterType getType() const
00453   {
00454     return this->parameterType;
00455   }
00456   ;
00457 
00458   bool value;
00459 
00460   std::string name;
00461 
00462   ParameterType parameterType;
00463 
00464 };
00468 class JointLimits : public YouBotApiJointParameter
00469 {
00470   friend class YouBotJoint;
00471 public:
00472   JointLimits();
00473 
00474   virtual ~JointLimits();
00475 
00476   void getParameter(int& lowerLimit, int& upperLimit, bool& areLimitsActive) const;
00477 
00478   void setParameter(const int lowerLimit, const int upperLimit, const bool activateLimits);
00479 
00480   void toString(std::string& value);
00481 
00482 private:
00483   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00484                            const YouBotJointStorage& storage) const
00485   {
00486   }
00487   ;
00488 
00489   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00490   {
00491   }
00492   ;
00493 
00494   std::string getName() const
00495   {
00496     return this->name;
00497   }
00498   ;
00499 
00500   ParameterType getType() const
00501   {
00502     return this->parameterType;
00503   }
00504   ;
00505 
00506   int lowerLimit;
00507 
00508   int upperLimit;
00509 
00510   std::string name;
00511 
00512   ParameterType parameterType;
00513 
00514   bool areLimitsActive;
00515 
00516 };
00520 class JointLimitsRadian : public YouBotApiJointParameter
00521 {
00522   friend class YouBotJoint;
00523 public:
00524   JointLimitsRadian();
00525 
00526   virtual ~JointLimitsRadian();
00527 
00528   void getParameter(quantity<plane_angle>& lowerLimit, quantity<plane_angle>& upperLimit, bool& areLimitsActive) const;
00529 
00530   void setParameter(const quantity<plane_angle>& lowerLimit, const quantity<plane_angle>& upperLimit,
00531                     const bool activateLimits);
00532 
00533   void toString(std::string& value);
00534 
00535 private:
00536   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00537                            const YouBotJointStorage& storage) const
00538   {
00539   }
00540   ;
00541 
00542   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00543   {
00544   }
00545   ;
00546 
00547   std::string getName() const
00548   {
00549     return this->name;
00550   }
00551   ;
00552 
00553   ParameterType getType() const
00554   {
00555     return this->parameterType;
00556   }
00557   ;
00558 
00559   quantity<plane_angle> lowerLimit;
00560 
00561   quantity<plane_angle> upperLimit;
00562 
00563   std::string name;
00564 
00565   ParameterType parameterType;
00566 
00567   bool areLimitsActive;
00568 
00569 };
00573 class TorqueConstant : public YouBotApiJointParameter
00574 {
00575   friend class YouBotJoint;
00576 public:
00577   TorqueConstant();
00578 
00579   virtual ~TorqueConstant();
00580 
00581   void getParameter(double& parameter) const;
00582 
00583   void setParameter(const double parameter);
00584 
00585   void toString(std::string& value);
00586 
00587 private:
00588   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00589                            const YouBotJointStorage& storage) const
00590   {
00591   }
00592   ;
00593 
00594   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage)
00595   {
00596   }
00597   ;
00598 
00599   std::string getName() const
00600   {
00601     return this->name;
00602   }
00603   ;
00604 
00605   ParameterType getType() const
00606   {
00607     return this->parameterType;
00608   }
00609   ;
00610 
00611   double value;
00612 
00613   std::string name;
00614 
00615   ParameterType parameterType;
00616 
00617 };
00621 class MaximumPositioningVelocity : public YouBotJointParameter
00622 {
00623   friend class YouBotJoint;
00624 public:
00625   MaximumPositioningVelocity();
00626 
00627   virtual ~MaximumPositioningVelocity();
00628 
00629   void getParameter(quantity<angular_velocity>& parameter) const;
00630 
00631   void setParameter(const quantity<angular_velocity>& parameter);
00632 
00633   void toString(std::string& value);
00634 
00635 private:
00636   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00637                            const YouBotJointStorage& storage) const;
00638 
00639   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00640 
00641   std::string getName() const
00642   {
00643     return this->name;
00644   }
00645   ;
00646 
00647   ParameterType getType() const
00648   {
00649     return this->parameterType;
00650   }
00651   ;
00652 
00653   quantity<angular_velocity> upperLimit;
00654 
00655   quantity<angular_velocity> lowerLimit;
00656 
00657   quantity<angular_velocity> value;
00658 
00659   std::string name;
00660 
00661   ParameterType parameterType;
00662 
00663 };
00667 class MotorAcceleration : public YouBotJointParameter
00668 {
00669   friend class YouBotJoint;
00670 public:
00671   MotorAcceleration();
00672 
00673   virtual ~MotorAcceleration();
00674 
00675   void getParameter(quantity<angular_acceleration>& parameter) const;
00676 
00677   void setParameter(const quantity<angular_acceleration>& parameter);
00678 
00679   void toString(std::string& value);
00680 
00681 private:
00682   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00683                            const YouBotJointStorage& storage) const;
00684 
00685   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00686 
00687   std::string getName() const
00688   {
00689     return this->name;
00690   }
00691   ;
00692 
00693   ParameterType getType() const
00694   {
00695     return this->parameterType;
00696   }
00697   ;
00698 
00699   quantity<angular_acceleration> upperLimit;
00700 
00701   quantity<angular_acceleration> lowerLimit;
00702 
00703   quantity<angular_acceleration> value;
00704 
00705   std::string name;
00706 
00707   ParameterType parameterType;
00708 
00709 };
00713 class RampGeneratorSpeedAndPositionControl : public YouBotJointParameter
00714 {
00715   friend class YouBotJoint;
00716 public:
00717   RampGeneratorSpeedAndPositionControl();
00718 
00719   virtual ~RampGeneratorSpeedAndPositionControl();
00720 
00721   void getParameter(bool& parameter) const;
00722 
00723   void setParameter(const bool parameter);
00724 
00725   void toString(std::string& value);
00726 
00727 private:
00728   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00729                            const YouBotJointStorage& storage) const;
00730 
00731   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00732 
00733   std::string getName() const
00734   {
00735     return this->name;
00736   }
00737   ;
00738 
00739   ParameterType getType() const
00740   {
00741     return this->parameterType;
00742   }
00743   ;
00744 
00745   bool value;
00746 
00747   std::string name;
00748 
00749   ParameterType parameterType;
00750 
00751 };
00755 class PositionControlSwitchingThreshold : public YouBotJointParameter
00756 {
00757   friend class YouBotJoint;
00758 public:
00759   PositionControlSwitchingThreshold();
00760 
00761   virtual ~PositionControlSwitchingThreshold();
00762 
00763   void getParameter(quantity<angular_velocity>& parameter) const;
00764 
00765   void setParameter(const quantity<angular_velocity>& parameter);
00766 
00767   void toString(std::string& value);
00768 
00769 private:
00770   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00771                            const YouBotJointStorage& storage) const;
00772 
00773   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00774 
00775   std::string getName() const
00776   {
00777     return this->name;
00778   }
00779   ;
00780 
00781   ParameterType getType() const
00782   {
00783     return this->parameterType;
00784   }
00785   ;
00786 
00787   quantity<angular_velocity> upperLimit;
00788 
00789   quantity<angular_velocity> lowerLimit;
00790 
00791   quantity<angular_velocity> value;
00792 
00793   std::string name;
00794 
00795   ParameterType parameterType;
00796 
00797 };
00800 
00802 class SpeedControlSwitchingThreshold : public YouBotJointParameter
00803 {
00804   friend class YouBotJoint;
00805 public:
00806   SpeedControlSwitchingThreshold();
00807 
00808   virtual ~SpeedControlSwitchingThreshold();
00809 
00810   void getParameter(quantity<angular_velocity>& parameter) const;
00811 
00812   void setParameter(const quantity<angular_velocity>& parameter);
00813 
00814   void toString(std::string& value);
00815 
00816 private:
00817   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00818                            const YouBotJointStorage& storage) const;
00819 
00820   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00821 
00822   std::string getName() const
00823   {
00824     return this->name;
00825   }
00826   ;
00827 
00828   ParameterType getType() const
00829   {
00830     return this->parameterType;
00831   }
00832   ;
00833 
00834   quantity<angular_velocity> upperLimit;
00835 
00836   quantity<angular_velocity> lowerLimit;
00837 
00838   quantity<angular_velocity> value;
00839 
00840   std::string name;
00841 
00842   ParameterType parameterType;
00843 
00844 };
00848 class VelocityThresholdForHallFX : public YouBotJointParameter
00849 {
00850   friend class YouBotJoint;
00851 public:
00852   VelocityThresholdForHallFX();
00853 
00854   virtual ~VelocityThresholdForHallFX();
00855 
00856   void getParameter(quantity<angular_velocity>& parameter) const;
00857 
00858   void setParameter(const quantity<angular_velocity>& parameter);
00859 
00860   void toString(std::string& value);
00861 
00862 private:
00863   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00864                            const YouBotJointStorage& storage) const;
00865 
00866   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00867 
00868   std::string getName() const
00869   {
00870     return this->name;
00871   }
00872   ;
00873 
00874   ParameterType getType() const
00875   {
00876     return this->parameterType;
00877   }
00878   ;
00879 
00880   quantity<angular_velocity> upperLimit;
00881 
00882   quantity<angular_velocity> lowerLimit;
00883 
00884   quantity<angular_velocity> value;
00885 
00886   std::string name;
00887 
00888   ParameterType parameterType;
00889 
00890 };
00894 class PParameterFirstParametersPositionControl : public YouBotJointParameter
00895 {
00896   friend class YouBotJoint;
00897 public:
00898   PParameterFirstParametersPositionControl();
00899 
00900   virtual ~PParameterFirstParametersPositionControl();
00901 
00902   void getParameter(int& parameter) const;
00903 
00904   void setParameter(const int parameter);
00905 
00906   void toString(std::string& value);
00907 
00908 private:
00909   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00910                            const YouBotJointStorage& storage) const;
00911 
00912   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00913 
00914   std::string getName() const
00915   {
00916     return this->name;
00917   }
00918   ;
00919 
00920   ParameterType getType() const
00921   {
00922     return this->parameterType;
00923   }
00924   ;
00925 
00926   int upperLimit;
00927 
00928   int lowerLimit;
00929 
00930   int value;
00931 
00932   std::string name;
00933 
00934   ParameterType parameterType;
00935 
00936 };
00940 class IParameterFirstParametersPositionControl : public YouBotJointParameter
00941 {
00942   friend class YouBotJoint;
00943 public:
00944   IParameterFirstParametersPositionControl();
00945 
00946   virtual ~IParameterFirstParametersPositionControl();
00947 
00948   void getParameter(int& parameter) const;
00949 
00950   void setParameter(const int parameter);
00951 
00952   void toString(std::string& value);
00953 
00954 private:
00955   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
00956                            const YouBotJointStorage& storage) const;
00957 
00958   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
00959 
00960   std::string getName() const
00961   {
00962     return this->name;
00963   }
00964   ;
00965 
00966   ParameterType getType() const
00967   {
00968     return this->parameterType;
00969   }
00970   ;
00971 
00972   int upperLimit;
00973 
00974   int lowerLimit;
00975 
00976   int value;
00977 
00978   std::string name;
00979 
00980   ParameterType parameterType;
00981 
00982 };
00986 class DParameterFirstParametersPositionControl : public YouBotJointParameter
00987 {
00988   friend class YouBotJoint;
00989 public:
00990   DParameterFirstParametersPositionControl();
00991 
00992   virtual ~DParameterFirstParametersPositionControl();
00993 
00994   void getParameter(int& parameter) const;
00995 
00996   void setParameter(const int parameter);
00997 
00998   void toString(std::string& value);
00999 
01000 private:
01001   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01002                            const YouBotJointStorage& storage) const;
01003 
01004   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01005 
01006   std::string getName() const
01007   {
01008     return this->name;
01009   }
01010   ;
01011 
01012   ParameterType getType() const
01013   {
01014     return this->parameterType;
01015   }
01016   ;
01017 
01018   int upperLimit;
01019 
01020   int lowerLimit;
01021 
01022   int value;
01023 
01024   std::string name;
01025 
01026   ParameterType parameterType;
01027 
01028 };
01032 class IClippingParameterFirstParametersPositionControl : public YouBotJointParameter
01033 {
01034   friend class YouBotJoint;
01035 public:
01036   IClippingParameterFirstParametersPositionControl();
01037 
01038   virtual ~IClippingParameterFirstParametersPositionControl();
01039 
01040   void getParameter(int& parameter) const;
01041 
01042   void setParameter(const int parameter);
01043 
01044   void toString(std::string& value);
01045 
01046 private:
01047   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01048                            const YouBotJointStorage& storage) const;
01049 
01050   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01051 
01052   std::string getName() const
01053   {
01054     return this->name;
01055   }
01056   ;
01057 
01058   ParameterType getType() const
01059   {
01060     return this->parameterType;
01061   }
01062   ;
01063 
01064   int upperLimit;
01065 
01066   int lowerLimit;
01067 
01068   int value;
01069 
01070   std::string name;
01071 
01072   ParameterType parameterType;
01073 
01074 };
01078 class PParameterFirstParametersSpeedControl : public YouBotJointParameter
01079 {
01080   friend class YouBotJoint;
01081 public:
01082   PParameterFirstParametersSpeedControl();
01083 
01084   virtual ~PParameterFirstParametersSpeedControl();
01085 
01086   void getParameter(int& parameter) const;
01087 
01088   void setParameter(const int parameter);
01089 
01090   void toString(std::string& value);
01091 
01092 private:
01093   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01094                            const YouBotJointStorage& storage) const;
01095 
01096   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01097 
01098   std::string getName() const
01099   {
01100     return this->name;
01101   }
01102   ;
01103 
01104   ParameterType getType() const
01105   {
01106     return this->parameterType;
01107   }
01108   ;
01109 
01110   int upperLimit;
01111 
01112   int lowerLimit;
01113 
01114   int value;
01115 
01116   std::string name;
01117 
01118   ParameterType parameterType;
01119 
01120 };
01124 class IParameterFirstParametersSpeedControl : public YouBotJointParameter
01125 {
01126   friend class YouBotJoint;
01127 public:
01128   IParameterFirstParametersSpeedControl();
01129 
01130   virtual ~IParameterFirstParametersSpeedControl();
01131 
01132   void getParameter(int& parameter) const;
01133 
01134   void setParameter(const int parameter);
01135 
01136   void toString(std::string& value);
01137 
01138 private:
01139   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01140                            const YouBotJointStorage& storage) const;
01141 
01142   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01143 
01144   std::string getName() const
01145   {
01146     return this->name;
01147   }
01148   ;
01149 
01150   ParameterType getType() const
01151   {
01152     return this->parameterType;
01153   }
01154   ;
01155 
01156   int upperLimit;
01157 
01158   int lowerLimit;
01159 
01160   int value;
01161 
01162   std::string name;
01163 
01164   ParameterType parameterType;
01165 
01166 };
01170 class DParameterFirstParametersSpeedControl : public YouBotJointParameter
01171 {
01172   friend class YouBotJoint;
01173 public:
01174   DParameterFirstParametersSpeedControl();
01175 
01176   virtual ~DParameterFirstParametersSpeedControl();
01177 
01178   void getParameter(int& parameter) const;
01179 
01180   void setParameter(const int parameter);
01181 
01182   void toString(std::string& value);
01183 
01184 private:
01185   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01186                            const YouBotJointStorage& storage) const;
01187 
01188   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01189 
01190   std::string getName() const
01191   {
01192     return this->name;
01193   }
01194   ;
01195 
01196   ParameterType getType() const
01197   {
01198     return this->parameterType;
01199   }
01200   ;
01201 
01202   int upperLimit;
01203 
01204   int lowerLimit;
01205 
01206   int value;
01207 
01208   std::string name;
01209 
01210   ParameterType parameterType;
01211 
01212 };
01216 class IClippingParameterFirstParametersSpeedControl : public YouBotJointParameter
01217 {
01218   friend class YouBotJoint;
01219 public:
01220   IClippingParameterFirstParametersSpeedControl();
01221 
01222   virtual ~IClippingParameterFirstParametersSpeedControl();
01223 
01224   void getParameter(int& parameter) const;
01225 
01226   void setParameter(const int parameter);
01227 
01228   void toString(std::string& value);
01229 
01230 private:
01231   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01232                            const YouBotJointStorage& storage) const;
01233 
01234   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01235 
01236   std::string getName() const
01237   {
01238     return this->name;
01239   }
01240   ;
01241 
01242   ParameterType getType() const
01243   {
01244     return this->parameterType;
01245   }
01246   ;
01247 
01248   int upperLimit;
01249 
01250   int lowerLimit;
01251 
01252   int value;
01253 
01254   std::string name;
01255 
01256   ParameterType parameterType;
01257 
01258 };
01262 class PParameterSecondParametersPositionControl : public YouBotJointParameter
01263 {
01264   friend class YouBotJoint;
01265 public:
01266   PParameterSecondParametersPositionControl();
01267 
01268   virtual ~PParameterSecondParametersPositionControl();
01269 
01270   void getParameter(int& parameter) const;
01271 
01272   void setParameter(const int parameter);
01273 
01274   void toString(std::string& value);
01275 
01276 private:
01277   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01278                            const YouBotJointStorage& storage) const;
01279 
01280   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01281 
01282   std::string getName() const
01283   {
01284     return this->name;
01285   }
01286   ;
01287 
01288   ParameterType getType() const
01289   {
01290     return this->parameterType;
01291   }
01292   ;
01293 
01294   int upperLimit;
01295 
01296   int lowerLimit;
01297 
01298   int value;
01299 
01300   std::string name;
01301 
01302   ParameterType parameterType;
01303 
01304 };
01308 class IParameterSecondParametersPositionControl : public YouBotJointParameter
01309 {
01310   friend class YouBotJoint;
01311 public:
01312   IParameterSecondParametersPositionControl();
01313 
01314   virtual ~IParameterSecondParametersPositionControl();
01315 
01316   void getParameter(int& parameter) const;
01317 
01318   void setParameter(const int parameter);
01319 
01320   void toString(std::string& value);
01321 
01322 private:
01323   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01324                            const YouBotJointStorage& storage) const;
01325 
01326   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01327 
01328   std::string getName() const
01329   {
01330     return this->name;
01331   }
01332   ;
01333 
01334   ParameterType getType() const
01335   {
01336     return this->parameterType;
01337   }
01338   ;
01339 
01340   int upperLimit;
01341 
01342   int lowerLimit;
01343 
01344   int value;
01345 
01346   std::string name;
01347 
01348   ParameterType parameterType;
01349 
01350 };
01354 class DParameterSecondParametersPositionControl : public YouBotJointParameter
01355 {
01356   friend class YouBotJoint;
01357 public:
01358   DParameterSecondParametersPositionControl();
01359 
01360   virtual ~DParameterSecondParametersPositionControl();
01361 
01362   void getParameter(int& parameter) const;
01363 
01364   void setParameter(const int parameter);
01365 
01366   void toString(std::string& value);
01367 
01368 private:
01369   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01370                            const YouBotJointStorage& storage) const;
01371 
01372   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01373 
01374   std::string getName() const
01375   {
01376     return this->name;
01377   }
01378   ;
01379 
01380   ParameterType getType() const
01381   {
01382     return this->parameterType;
01383   }
01384   ;
01385 
01386   int upperLimit;
01387 
01388   int lowerLimit;
01389 
01390   int value;
01391 
01392   std::string name;
01393 
01394   ParameterType parameterType;
01395 
01396 };
01400 class IClippingParameterSecondParametersPositionControl : public YouBotJointParameter
01401 {
01402   friend class YouBotJoint;
01403 public:
01404   IClippingParameterSecondParametersPositionControl();
01405 
01406   virtual ~IClippingParameterSecondParametersPositionControl();
01407 
01408   void getParameter(int& parameter) const;
01409 
01410   void setParameter(const int parameter);
01411 
01412   void toString(std::string& value);
01413 
01414 private:
01415   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01416                            const YouBotJointStorage& storage) const;
01417 
01418   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01419 
01420   std::string getName() const
01421   {
01422     return this->name;
01423   }
01424   ;
01425 
01426   ParameterType getType() const
01427   {
01428     return this->parameterType;
01429   }
01430   ;
01431 
01432   int upperLimit;
01433 
01434   int lowerLimit;
01435 
01436   int value;
01437 
01438   std::string name;
01439 
01440   ParameterType parameterType;
01441 
01442 };
01446 class PParameterSecondParametersSpeedControl : public YouBotJointParameter
01447 {
01448   friend class YouBotJoint;
01449 public:
01450   PParameterSecondParametersSpeedControl();
01451 
01452   virtual ~PParameterSecondParametersSpeedControl();
01453 
01454   void getParameter(int& parameter) const;
01455 
01456   void setParameter(const int parameter);
01457 
01458   void toString(std::string& value);
01459 
01460 private:
01461   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01462                            const YouBotJointStorage& storage) const;
01463 
01464   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01465 
01466   std::string getName() const
01467   {
01468     return this->name;
01469   }
01470   ;
01471 
01472   ParameterType getType() const
01473   {
01474     return this->parameterType;
01475   }
01476   ;
01477 
01478   int upperLimit;
01479 
01480   int lowerLimit;
01481 
01482   int value;
01483 
01484   std::string name;
01485 
01486   ParameterType parameterType;
01487 
01488 };
01492 class IParameterSecondParametersSpeedControl : public YouBotJointParameter
01493 {
01494   friend class YouBotJoint;
01495 public:
01496   IParameterSecondParametersSpeedControl();
01497 
01498   virtual ~IParameterSecondParametersSpeedControl();
01499 
01500   void getParameter(int& parameter) const;
01501 
01502   void setParameter(const int parameter);
01503 
01504   void toString(std::string& value);
01505 
01506 private:
01507   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01508                            const YouBotJointStorage& storage) const;
01509 
01510   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01511 
01512   std::string getName() const
01513   {
01514     return this->name;
01515   }
01516   ;
01517 
01518   ParameterType getType() const
01519   {
01520     return this->parameterType;
01521   }
01522   ;
01523 
01524   int upperLimit;
01525 
01526   int lowerLimit;
01527 
01528   int value;
01529 
01530   std::string name;
01531 
01532   ParameterType parameterType;
01533 
01534 };
01538 class DParameterSecondParametersSpeedControl : public YouBotJointParameter
01539 {
01540   friend class YouBotJoint;
01541 public:
01542   DParameterSecondParametersSpeedControl();
01543 
01544   virtual ~DParameterSecondParametersSpeedControl();
01545 
01546   void getParameter(int& parameter) const;
01547 
01548   void setParameter(const int parameter);
01549 
01550   void toString(std::string& value);
01551 
01552 private:
01553   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01554                            const YouBotJointStorage& storage) const;
01555 
01556   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01557 
01558   std::string getName() const
01559   {
01560     return this->name;
01561   }
01562   ;
01563 
01564   ParameterType getType() const
01565   {
01566     return this->parameterType;
01567   }
01568   ;
01569 
01570   int upperLimit;
01571 
01572   int lowerLimit;
01573 
01574   int value;
01575 
01576   std::string name;
01577 
01578   ParameterType parameterType;
01579 
01580 };
01584 class IClippingParameterSecondParametersSpeedControl : public YouBotJointParameter
01585 {
01586   friend class YouBotJoint;
01587 public:
01588   IClippingParameterSecondParametersSpeedControl();
01589 
01590   virtual ~IClippingParameterSecondParametersSpeedControl();
01591 
01592   void getParameter(int& parameter) const;
01593 
01594   void setParameter(const int parameter);
01595 
01596   void toString(std::string& value);
01597 
01598 private:
01599   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01600                            const YouBotJointStorage& storage) const;
01601 
01602   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01603 
01604   std::string getName() const
01605   {
01606     return this->name;
01607   }
01608   ;
01609 
01610   ParameterType getType() const
01611   {
01612     return this->parameterType;
01613   }
01614   ;
01615 
01616   int upperLimit;
01617 
01618   int lowerLimit;
01619 
01620   int value;
01621 
01622   std::string name;
01623 
01624   ParameterType parameterType;
01625 
01626 };
01630 class PParameterCurrentControl : public YouBotJointParameter
01631 {
01632   friend class YouBotJoint;
01633 public:
01634   PParameterCurrentControl();
01635 
01636   virtual ~PParameterCurrentControl();
01637 
01638   void getParameter(int& parameter) const;
01639 
01640   void setParameter(const int parameter);
01641 
01642   void toString(std::string& value);
01643 
01644 private:
01645   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01646                            const YouBotJointStorage& storage) const;
01647 
01648   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01649 
01650   std::string getName() const
01651   {
01652     return this->name;
01653   }
01654   ;
01655 
01656   ParameterType getType() const
01657   {
01658     return this->parameterType;
01659   }
01660   ;
01661 
01662   int upperLimit;
01663 
01664   int lowerLimit;
01665 
01666   int value;
01667 
01668   std::string name;
01669 
01670   ParameterType parameterType;
01671 
01672 };
01676 class IParameterCurrentControl : public YouBotJointParameter
01677 {
01678   friend class YouBotJoint;
01679 public:
01680   IParameterCurrentControl();
01681 
01682   virtual ~IParameterCurrentControl();
01683 
01684   void getParameter(int& parameter) const;
01685 
01686   void setParameter(const int parameter);
01687 
01688   void toString(std::string& value);
01689 
01690 private:
01691   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01692                            const YouBotJointStorage& storage) const;
01693 
01694   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01695 
01696   std::string getName() const
01697   {
01698     return this->name;
01699   }
01700   ;
01701 
01702   ParameterType getType() const
01703   {
01704     return this->parameterType;
01705   }
01706   ;
01707 
01708   int upperLimit;
01709 
01710   int lowerLimit;
01711 
01712   int value;
01713 
01714   std::string name;
01715 
01716   ParameterType parameterType;
01717 
01718 };
01722 class DParameterCurrentControl : public YouBotJointParameter
01723 {
01724   friend class YouBotJoint;
01725 public:
01726   DParameterCurrentControl();
01727 
01728   virtual ~DParameterCurrentControl();
01729 
01730   void getParameter(int& parameter) const;
01731 
01732   void setParameter(const int parameter);
01733 
01734   void toString(std::string& value);
01735 
01736 private:
01737   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01738                            const YouBotJointStorage& storage) const;
01739 
01740   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01741 
01742   std::string getName() const
01743   {
01744     return this->name;
01745   }
01746   ;
01747 
01748   ParameterType getType() const
01749   {
01750     return this->parameterType;
01751   }
01752   ;
01753 
01754   int upperLimit;
01755 
01756   int lowerLimit;
01757 
01758   int value;
01759 
01760   std::string name;
01761 
01762   ParameterType parameterType;
01763 
01764 };
01768 class IClippingParameterCurrentControl : public YouBotJointParameter
01769 {
01770   friend class YouBotJoint;
01771 public:
01772   IClippingParameterCurrentControl();
01773 
01774   virtual ~IClippingParameterCurrentControl();
01775 
01776   void getParameter(int& parameter) const;
01777 
01778   void setParameter(const int parameter);
01779 
01780   void toString(std::string& value);
01781 
01782 private:
01783   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01784                            const YouBotJointStorage& storage) const;
01785 
01786   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01787 
01788   std::string getName() const
01789   {
01790     return this->name;
01791   }
01792   ;
01793 
01794   ParameterType getType() const
01795   {
01796     return this->parameterType;
01797   }
01798   ;
01799 
01800   int upperLimit;
01801 
01802   int lowerLimit;
01803 
01804   int value;
01805 
01806   std::string name;
01807 
01808   ParameterType parameterType;
01809 
01810 };
01814 class MaximumVelocityToSetPosition : public YouBotJointParameter
01815 {
01816   friend class YouBotJoint;
01817 public:
01818   MaximumVelocityToSetPosition();
01819 
01820   virtual ~MaximumVelocityToSetPosition();
01821 
01822   void getParameter(quantity<angular_velocity>& parameter) const;
01823 
01824   void setParameter(const quantity<angular_velocity>& parameter);
01825 
01826   void toString(std::string& value);
01827 
01828 private:
01829   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01830                            const YouBotJointStorage& storage) const;
01831 
01832   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01833 
01834   std::string getName() const
01835   {
01836     return this->name;
01837   }
01838   ;
01839 
01840   ParameterType getType() const
01841   {
01842     return this->parameterType;
01843   }
01844   ;
01845 
01846   quantity<angular_velocity> upperLimit;
01847 
01848   quantity<angular_velocity> lowerLimit;
01849 
01850   quantity<angular_velocity> value;
01851 
01852   std::string name;
01853 
01854   ParameterType parameterType;
01855 
01856 };
01860 class PositionTargetReachedDistance : public YouBotJointParameter
01861 {
01862   friend class YouBotJoint;
01863 public:
01864   PositionTargetReachedDistance();
01865 
01866   virtual ~PositionTargetReachedDistance();
01867 
01868   void getParameter(int& parameter) const;
01869 
01870   void setParameter(const int parameter);
01871 
01872   void toString(std::string& value);
01873 
01874 private:
01875   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01876                            const YouBotJointStorage& storage) const;
01877 
01878   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01879 
01880   std::string getName() const
01881   {
01882     return this->name;
01883   }
01884   ;
01885 
01886   ParameterType getType() const
01887   {
01888     return this->parameterType;
01889   }
01890   ;
01891 
01892   int upperLimit;
01893 
01894   int lowerLimit;
01895 
01896   int value;
01897 
01898   std::string name;
01899 
01900   ParameterType parameterType;
01901 
01902 };
01906 class ClearI2tExceededFlag : public YouBotJointParameter
01907 {
01908   friend class YouBotJoint;
01909 public:
01910   ClearI2tExceededFlag();
01911 
01912   virtual ~ClearI2tExceededFlag();
01913 
01914   void getParameter() const;
01915 
01916   void setParameter();
01917 
01918   void toString(std::string& value);
01919 
01920 private:
01921   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01922                            const YouBotJointStorage& storage) const;
01923 
01924   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01925 
01926   std::string getName() const
01927   {
01928     return this->name;
01929   }
01930   ;
01931 
01932   ParameterType getType() const
01933   {
01934     return this->parameterType;
01935   }
01936   ;
01937 
01938   bool value;
01939 
01940   std::string name;
01941 
01942   ParameterType parameterType;
01943 
01944 };
01947 
01949 class ClearMotorControllerTimeoutFlag : public YouBotJointParameter
01950 {
01951   friend class YouBotJoint;
01952 public:
01953   ClearMotorControllerTimeoutFlag();
01954 
01955   virtual ~ClearMotorControllerTimeoutFlag();
01956 
01957   bool getParameter() const;
01958 
01959   void setParameter();
01960 
01961   void toString(std::string& value);
01962 
01963 private:
01964   void getYouBotMailboxMsg(YouBotSlaveMailboxMsg& message, TMCLCommandNumber msgType,
01965                            const YouBotJointStorage& storage) const;
01966 
01967   void setYouBotMailboxMsg(const YouBotSlaveMailboxMsg& message, const YouBotJointStorage& storage);
01968 
01969   std::string getName() const
01970   {
01971     return this->name;
01972   }
01973   ;
01974 
01975   ParameterType getType() const
01976   {
01977     return this->parameterType;
01978   }
01979   ;
01980 
01981   bool value;
01982 
01983   std::string name;
01984 
01985   ParameterType parameterType;
01986 
01987 };
01991 class PParameterTrajectoryControl : public YouBotApiJointParameter
01992 {
01993   friend class YouBotJoint;
01994 public:
01995   PParameterTrajectoryControl();
01996 
01997   virtual ~PParameterTrajectoryControl();
01998 
01999   void getParameter(double& parameter) const;
02000 
02001   void setParameter(const double parameter);
02002 
02003   void toString(std::string& value);
02004 
02005 private:
02006   std::string getName() const
02007   {
02008     return this->name;
02009   }
02010   ;
02011 
02012   ParameterType getType() const
02013   {
02014     return this->parameterType;
02015   }
02016   ;
02017 
02018   double upperLimit;
02019 
02020   double lowerLimit;
02021 
02022   double value;
02023 
02024   std::string name;
02025 
02026   ParameterType parameterType;
02027 
02028 };
02032 class IParameterTrajectoryControl : public YouBotApiJointParameter
02033 {
02034   friend class YouBotJoint;
02035 public:
02036   IParameterTrajectoryControl();
02037 
02038   virtual ~IParameterTrajectoryControl();
02039 
02040   void getParameter(double& parameter) const;
02041 
02042   void setParameter(const double parameter);
02043 
02044   void toString(std::string& value);
02045 
02046 private:
02047   std::string getName() const
02048   {
02049     return this->name;
02050   }
02051   ;
02052 
02053   ParameterType getType() const
02054   {
02055     return this->parameterType;
02056   }
02057   ;
02058 
02059   double upperLimit;
02060 
02061   double lowerLimit;
02062 
02063   double value;
02064 
02065   std::string name;
02066 
02067   ParameterType parameterType;
02068 
02069 };
02073 class DParameterTrajectoryControl : public YouBotApiJointParameter
02074 {
02075   friend class YouBotJoint;
02076 public:
02077   DParameterTrajectoryControl();
02078 
02079   virtual ~DParameterTrajectoryControl();
02080 
02081   void getParameter(double& parameter) const;
02082 
02083   void setParameter(const double parameter);
02084 
02085   void toString(std::string& value);
02086 
02087 private:
02088   std::string getName() const
02089   {
02090     return this->name;
02091   }
02092   ;
02093 
02094   ParameterType getType() const
02095   {
02096     return this->parameterType;
02097   }
02098   ;
02099 
02100   double upperLimit;
02101 
02102   double lowerLimit;
02103 
02104   double value;
02105 
02106   std::string name;
02107 
02108   ParameterType parameterType;
02109 
02110 };
02114 class IClippingParameterTrajectoryControl : public YouBotApiJointParameter
02115 {
02116   friend class YouBotJoint;
02117 public:
02118   IClippingParameterTrajectoryControl();
02119 
02120   virtual ~IClippingParameterTrajectoryControl();
02121 
02122   void getParameter(double& parameter) const;
02123 
02124   void setParameter(const double parameter);
02125 
02126   void toString(std::string& value);
02127 
02128 private:
02129   std::string getName() const
02130   {
02131     return this->name;
02132   }
02133   ;
02134 
02135   ParameterType getType() const
02136   {
02137     return this->parameterType;
02138   }
02139   ;
02140 
02141   double upperLimit;
02142 
02143   double lowerLimit;
02144 
02145   double value;
02146 
02147   std::string name;
02148 
02149   ParameterType parameterType;
02150 
02151 };
02152 
02153 } // namespace youbot
02154 #endif


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