Message_data.h
Go to the documentation of this file.
00001 
00038 #ifndef SAWYER_MESSAGE_DATA_H
00039 #define SAWYER_MESSAGE_DATA_H
00040 
00041 #include <iostream>
00042 #include <string>
00043 #include <stdint.h>
00044 #include "roch_base/core/Message.h"
00045 #include "roch_base/core/Message_request.h"
00046 #include <boost/concept_check.hpp>
00047 
00048 namespace sawyer
00049 {
00050 
00051   class DataAckermannOutput : public Message
00052   {
00053   public:
00054     enum payloadOffsets
00055     {
00056       STEERING = 0,
00057       THROTTLE = 2,
00058       BRAKE = 4,
00059       PAYLOAD_LEN = 6
00060     };
00061   public:
00062     DataAckermannOutput(void *input, size_t msg_len);
00063 
00064     DataAckermannOutput(const DataAckermannOutput &other);
00065 
00066     static DataAckermannOutput *popNext();
00067 
00068     static DataAckermannOutput *waitNext(double timeout = 0);
00069 
00070     static DataAckermannOutput *getUpdate(double timeout = 0);
00071 
00072     static void subscribe(uint16_t freq = 0);
00073 
00074     static enum MessageTypes getTypeID();
00075 
00076     double getSteering();
00077 
00078     double getThrottle();
00079 
00080     double getBrake();
00081 
00082     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00083   };
00084 
00085   class DataDifferentialControl : public Message
00086   {
00087   public:
00088     enum payloadOffsets
00089     {
00090       LEFT_P = 0,
00091       LEFT_I = 2,
00092       LEFT_D = 4,    
00093       RIGHT_P = 6,
00094       RIGHT_I = 8,
00095       RIGHT_D = 10,
00096       PAYLOAD_LEN = 12
00097     };
00098 
00099   public:
00100     DataDifferentialControl(void *input, size_t msg_len);
00101 
00102     DataDifferentialControl(const DataDifferentialControl &other);
00103 
00104     static DataDifferentialControl *popNext();
00105 
00106     static DataDifferentialControl *waitNext(double timeout = 0);
00107 
00108     static DataDifferentialControl *getUpdate(double timeout = 0);
00109 
00110     static void subscribe(uint16_t freq = 0);
00111 
00112     static enum MessageTypes getTypeID();
00113 
00114     double getLeftP();
00115 
00116     double getLeftI();
00117 
00118     double getLeftD();
00119 
00120     double getRightP();
00121 
00122     double getRightI();
00123 
00124     double getRightD();
00125 
00126     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00127   };
00128 
00129   class DataDifferentialOutput : public Message
00130   {
00131   public:
00132     enum payloadOffsets
00133     {
00134       LEFT = 0,
00135       RIGHT = 2,
00136       PAYLOAD_LEN = 4
00137     };
00138 
00139   public:
00140     DataDifferentialOutput(void *input, size_t msg_len);
00141 
00142     DataDifferentialOutput(const DataDifferentialOutput &other);
00143 
00144     static DataDifferentialOutput *popNext();
00145 
00146     static DataDifferentialOutput *waitNext(double timeout = 0);
00147 
00148     static DataDifferentialOutput *getUpdate(double timeout = 0);
00149 
00150     static void subscribe(uint16_t freq);
00151 
00152     static enum MessageTypes getTypeID();
00153 
00154     double getLeft();
00155 
00156     double getRight();
00157 
00158     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00159   };
00160 
00161   class DataDifferentialSpeed : public Message
00162   {
00163   public:
00164     enum payloadOffsets
00165     {
00166       LEFT_SPEED = 0,
00167       RIGHT_SPEED = 2,
00168       LEFT_ACCEL = 4,
00169       RIGHT_ACCEL = 6,
00170       PAYLOAD_LEN = 8
00171     };
00172 
00173   public:
00174     DataDifferentialSpeed(void *input, size_t msg_len);
00175 
00176     DataDifferentialSpeed(const DataDifferentialSpeed &other);
00177 
00178     static DataDifferentialSpeed *popNext();
00179 
00180     static DataDifferentialSpeed *waitNext(double timeout = 0);
00181 
00182     static DataDifferentialSpeed *getUpdate(double timeout = 0);
00183 
00184     static void subscribe(uint16_t freq);
00185 
00186     static enum MessageTypes getTypeID();
00187 
00188     double getLeftSpeed();
00189 
00190     double getLeftAccel();
00191 
00192     double getRightSpeed();
00193 
00194     double getRightAccel();
00195 
00196     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00197   };
00198 
00199   class DataWheelInfo : public Message
00200   {
00201   public:
00202     enum payloadOffsets
00203     {
00204       WHEEL_GAUGE = 0,
00205       WHEEL_DIAMETER = 2,
00206       PAYLOAD_LEN = 4
00207     };
00208 
00209   public:
00210     DataWheelInfo(void *input, size_t msg_len);
00211 
00212     DataWheelInfo(const DataWheelInfo &other);
00213 
00214     static DataWheelInfo *popNext();
00215 
00216     static DataWheelInfo *waitNext(double timeout = 0);
00217 
00218     static DataWheelInfo *getUpdate(double timeout = 0);
00219 
00220     static void subscribe(uint16_t freq);
00221 
00222     static enum MessageTypes getTypeID();
00223 
00224     double getWheelGauge();
00225 
00226     double getWheelDiameter();
00227 
00228     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00229   };
00230 
00231   class DataEcho : public Message
00232   {
00233   public:
00234     DataEcho(void *input, size_t msg_len);
00235 
00236     DataEcho(const DataEcho &other);
00237 
00238     static DataEcho *popNext();
00239 
00240     static DataEcho *waitNext(double timeout = 0);
00241 
00242     static DataEcho *getUpdate(double timeout = 0);
00243 
00244     static void subscribe(uint16_t freq);
00245 
00246     static enum MessageTypes getTypeID();
00247 
00248     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00249   };
00250 
00251   class DataEncoders : public Message
00252   {
00253   private:
00254     size_t travels_offset;
00255     size_t speeds_offset;
00256 
00257   public:
00258     DataEncoders(void *input, size_t msg_len);
00259 
00260     DataEncoders(const DataEncoders &other);
00261 
00262     static DataEncoders *popNext();
00263 
00264     static DataEncoders *waitNext(double timeout = 0);
00265 
00266     static DataEncoders *getUpdate(double timeout = 0);
00267 
00268     static void subscribe(uint16_t freq);
00269 
00270     static enum MessageTypes getTypeID();
00271 
00272     uint8_t getCount();
00273 
00274     double getTravel(uint8_t index);
00275 
00276     double getSpeed(uint8_t index);
00277 
00278     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00279   };
00280 
00281   class DataEncodersRaw : public Message
00282   {
00283   public:
00284     DataEncodersRaw(void *input, size_t pkt_len);
00285 
00286     DataEncodersRaw(const DataEncodersRaw &other);
00287 
00288     static DataEncodersRaw *popNext();
00289 
00290     static DataEncodersRaw *waitNext(double timeout = 0);
00291 
00292     static DataEncodersRaw *getUpdate(double timeout = 0);
00293 
00294     static void subscribe(uint16_t freq);
00295 
00296     static enum MessageTypes getTypeID();
00297 
00298     uint8_t getCount();
00299 
00300     int32_t getTicks(uint8_t inx);
00301 
00302     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00303   };
00304 
00305   class DataFirmwareInfo : public Message
00306   {
00307   public:
00308     enum payloadOffsets
00309     {
00310       MAJOR_FIRM_VER = 0,
00311       MINOR_FIRM_VER,
00312       MAJOR_PROTO_VER,
00313       MINOR_PROTO_VER,
00314       WRITE_TIME,
00315       PAYLOAD_LEN = 8
00316     };
00317 
00318     class WriteTime
00319     {
00320     public:
00321       uint32_t rawTime;
00322     public:
00323       WriteTime(uint32_t time) : rawTime(time)
00324       {
00325       }
00326 
00327       uint8_t minute()
00328       {
00329         return (rawTime) & 0x3f;
00330       }
00331 
00332       uint8_t hour()
00333       {
00334         return (rawTime >> 6) & 0x1f;
00335       }
00336 
00337       uint8_t day()
00338       {
00339         return (rawTime >> 11) & 0x3f;
00340       }
00341 
00342       uint8_t month()
00343       {
00344         return (rawTime >> 17) & 0x0f;
00345       }
00346 
00347       uint8_t year()
00348       {
00349         return (rawTime >> 21) & 0x7f;
00350       }
00351     };
00352 
00353   public:
00354     DataFirmwareInfo(void *input, size_t msg_len);
00355 
00356     DataFirmwareInfo(const DataFirmwareInfo &other);
00357 
00358     static DataFirmwareInfo *popNext();
00359 
00360     static DataFirmwareInfo *waitNext(double timeout = 0);
00361 
00362     static DataFirmwareInfo *getUpdate(double timeout = 0);
00363 
00364     static void subscribe(uint16_t freq);
00365 
00366     static enum MessageTypes getTypeID();
00367 
00368     uint8_t getMajorFirmwareVersion();
00369 
00370     uint8_t getMinorFirmwareVersion();
00371 
00372     uint8_t getMajorProtocolVersion();
00373 
00374     uint8_t getMinorProtocolVersion();
00375 
00376     WriteTime getWriteTime();
00377 
00378     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00379   };
00380 
00381   class DataGear : public Message
00382   {
00383   public:
00384     DataGear(void *input, size_t msg_len);
00385 
00386     DataGear(const DataGear &other);
00387 
00388     static DataGear *popNext();
00389 
00390     static DataGear *waitNext(double timeout = 0);
00391 
00392     static DataGear *getUpdate(double timeout = 0);
00393 
00394     static void subscribe(uint16_t freq);
00395 
00396     static enum MessageTypes getTypeID();
00397 
00398     uint8_t getGear();
00399 
00400     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00401   };
00402 
00403   class DataMaxAcceleration : public Message
00404   {
00405   public:
00406     enum payloadOffsets
00407     {
00408       FORWARD_MAX = 0,
00409       REVERSE_MAX = 2,
00410       PAYLOAD_LEN = 4
00411     };
00412 
00413   public:
00414     DataMaxAcceleration(void *input, size_t msg_len);
00415 
00416     DataMaxAcceleration(const DataMaxAcceleration &other);
00417 
00418     static DataMaxAcceleration *popNext();
00419 
00420     static DataMaxAcceleration *waitNext(double timeout = 0);
00421 
00422     static DataMaxAcceleration *getUpdate(double timeout = 0);
00423 
00424     static void subscribe(uint16_t freq);
00425 
00426     static enum MessageTypes getTypeID();
00427 
00428     double getForwardMax();
00429 
00430     double getReverseMax();
00431 
00432     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00433   };
00434 
00435   class DataMaxSpeed : public Message
00436   {
00437   public:
00438     enum payloadOffsets
00439     {
00440       FORWARD_MAX = 0,
00441       REVERSE_MAX = 2,
00442       PAYLOAD_LEN = 4
00443     };
00444 
00445   public:
00446     DataMaxSpeed(void *input, size_t msg_len);
00447 
00448     DataMaxSpeed(const DataMaxSpeed &other);
00449 
00450     static DataMaxSpeed *popNext();
00451 
00452     static DataMaxSpeed *waitNext(double timeout = 0);
00453 
00454     static DataMaxSpeed *getUpdate(double timeout = 0);
00455 
00456     static void subscribe(uint16_t freq);
00457 
00458     static enum MessageTypes getTypeID();
00459 
00460     double getForwardMax();
00461 
00462     double getReverseMax();
00463 
00464     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00465   };
00466 
00467   class DataPlatformAcceleration : public Message
00468   {
00469   public:
00470     enum payloadOffsets
00471     {
00472       X = 0,
00473       Y = 2,
00474       Z = 4,
00475       PAYLOAD_LEN = 6
00476     };
00477   public:
00478     DataPlatformAcceleration(void *input, size_t msg_len);
00479 
00480     DataPlatformAcceleration(const DataPlatformAcceleration &other);
00481 
00482     static DataPlatformAcceleration *popNext();
00483 
00484     static DataPlatformAcceleration *waitNext(double timeout = 0);
00485 
00486     static DataPlatformAcceleration *getUpdate(double timeout = 0);
00487 
00488     static void subscribe(uint16_t freq = 0);
00489 
00490     static enum MessageTypes getTypeID();
00491 
00492     double getX();
00493 
00494     double getY();
00495 
00496     double getZ();
00497 
00498     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00499   };
00500 
00501   class DataPlatformInfo : public Message
00502   {
00503   private:
00504     uint8_t strlenModel();
00505 
00506   public:
00507     DataPlatformInfo(void *input, size_t msg_len);
00508 
00509     DataPlatformInfo(const DataPlatformInfo &other);
00510 
00511     static DataPlatformInfo *popNext();
00512 
00513     static DataPlatformInfo *waitNext(double timeout = 0);
00514 
00515     static DataPlatformInfo *getUpdate(double timeout = 0);
00516 
00517     static void subscribe(uint16_t freq);
00518 
00519     static enum MessageTypes getTypeID();
00520 
00521     std::string getModel();
00522 
00523     uint8_t getRevision();
00524 
00525     uint32_t getSerial();
00526 
00527     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00528   };
00529 
00530   class DataPlatformName : public Message
00531   {
00532   public:
00533     DataPlatformName(void *input, size_t msg_len);
00534 
00535     DataPlatformName(const DataPlatformName &other);
00536 
00537     static DataPlatformName *popNext();
00538 
00539     static DataPlatformName *waitNext(double timeout = 0);
00540 
00541     static DataPlatformName *getUpdate(double timeout = 0);
00542 
00543     static void subscribe(uint16_t freq);
00544 
00545     static enum MessageTypes getTypeID();
00546 
00547     std::string getName();
00548 
00549     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00550   };
00551 
00552   class DataPlatformMagnetometer : public Message
00553   {
00554   public:
00555     enum payloadOffsets
00556     {
00557       X = 0,
00558       Y = 2,
00559       Z = 4,
00560       PAYLOAD_LEN = 6
00561     };
00562   public:
00563     DataPlatformMagnetometer(void *input, size_t msg_len);
00564 
00565     DataPlatformMagnetometer(const DataPlatformMagnetometer &other);
00566 
00567     static DataPlatformMagnetometer *popNext();
00568 
00569     static DataPlatformMagnetometer *waitNext(double timeout = 0);
00570 
00571     static DataPlatformMagnetometer *getUpdate(double timeout = 0);
00572 
00573     static void subscribe(uint16_t freq);
00574 
00575     static enum MessageTypes getTypeID();
00576 
00577     double getX();
00578 
00579     double getY();
00580 
00581     double getZ();
00582 
00583     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00584   };
00585 
00586   class DataPlatformOrientation : public Message
00587   {
00588   public:
00589     enum payloadOffsets
00590     {
00591       ROLL = 0,
00592       PITCH = 2,
00593       YAW = 4,
00594       PAYLOAD_LEN = 6
00595     };
00596   public:
00597     DataPlatformOrientation(void *input, size_t msg_len);
00598 
00599     DataPlatformOrientation(const DataPlatformOrientation &other);
00600 
00601     static DataPlatformOrientation *popNext();
00602 
00603     static DataPlatformOrientation *waitNext(double timeout = 0);
00604 
00605     static DataPlatformOrientation *getUpdate(double timeout = 0);
00606 
00607     static void subscribe(uint16_t freq);
00608 
00609     static enum MessageTypes getTypeID();
00610 
00611     double getRoll();
00612 
00613     double getYaw();
00614 
00615     double getPitch();
00616 
00617     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00618   };
00619 
00620   class DataPlatformRotation : public Message
00621   {
00622   public:
00623     enum payloadOffsets
00624     {
00625       ROLL_RATE = 0,
00626       PITCH_RATE = 2,
00627       YAW_RATE = 4,
00628       PAYLOAD_LEN = 6
00629     };
00630 
00631   public:
00632     DataPlatformRotation(void *input, size_t msg_len);
00633 
00634     DataPlatformRotation(const DataPlatformRotation &other);
00635 
00636     static DataPlatformRotation *popNext();
00637 
00638     static DataPlatformRotation *waitNext(double timeout = 0);
00639 
00640     static DataPlatformRotation *getUpdate(double timeout = 0);
00641 
00642     static void subscribe(uint16_t freq);
00643 
00644     static enum MessageTypes getTypeID();
00645 
00646     double getRollRate();
00647 
00648     double getPitchRate();
00649 
00650     double getYawRate();
00651 
00652     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00653   };
00654 
00655   class DataPowerSystem : public Message
00656   {
00657   public:
00658     class BatteryDescription
00659     {
00660     public:
00661       enum Types
00662       {
00663         EXTERNAL = 0x0,
00664         LEAD_ACID = 0x1,
00665         NIMH = 0x2,
00666         Li_ion = 0x3,
00667         GASOLINE = 0x8
00668       };
00669       uint8_t rawDesc;
00670     public:
00671       BatteryDescription(uint8_t desc) : rawDesc(desc)
00672       {
00673       }
00674 
00675       bool isPresent()
00676       {
00677         return rawDesc & 0x80;
00678       }
00679 
00680       bool isInUse()
00681       {
00682         return rawDesc & 0x40;
00683       }
00684 
00685       enum Types getType()
00686       {
00687         return (enum Types) (rawDesc & 0x0f);
00688       }
00689     };
00690 
00691   public:
00692     DataPowerSystem(void *input, size_t msg_len);
00693 
00694     DataPowerSystem(const DataPowerSystem &other);
00695 
00696     static DataPowerSystem *popNext();
00697 
00698     static DataPowerSystem *waitNext(double timeout = 0);
00699 
00700     static DataPowerSystem *getUpdate(double timeout = 0);
00701 
00702     static void subscribe(uint16_t freq);
00703 
00704     static enum MessageTypes getTypeID();
00705 
00706     uint8_t getBatteryCount();
00707 
00708     double getChargeEstimate(uint8_t battery);
00709 
00710     int16_t getCapacityEstimate(uint8_t battery);
00711 
00712     BatteryDescription getDescription(uint8_t battery);
00713 
00714     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00715   };
00716 
00717   class DataProcessorStatus : public Message
00718   {
00719   public:
00720     DataProcessorStatus(void *input, size_t msg_len);
00721 
00722     DataProcessorStatus(const DataProcessorStatus &other);
00723 
00724     static DataProcessorStatus *popNext();
00725 
00726     static DataProcessorStatus *waitNext(double timeout = 0);
00727 
00728     static DataProcessorStatus *getUpdate(double timeout = 0);
00729 
00730     static void subscribe(uint16_t freq);
00731 
00732     static enum MessageTypes getTypeID();
00733 
00734     uint8_t getProcessCount();
00735 
00736     int16_t getErrorCount(int process);
00737 
00738     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00739   };
00740 
00741   class DataRangefinders : public Message
00742   {
00743   public:
00744     DataRangefinders(void *input, size_t msg_len);
00745 
00746     DataRangefinders(const DataRangefinders &other);
00747 
00748     static DataRangefinders *popNext();
00749 
00750     static DataRangefinders *waitNext(double timeout = 0);
00751 
00752     static DataRangefinders *getUpdate(double timeout = 0);
00753 
00754     static void subscribe(uint16_t freq);
00755 
00756     static enum MessageTypes getTypeID();
00757 
00758     uint8_t getRangefinderCount();
00759 
00760     double getDistance(int rangefinder);
00761 
00762     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00763   };
00764 
00765   class DataRangefinderTimings : public Message
00766   {
00767   public:
00768     DataRangefinderTimings(void *input, size_t msg_len);
00769 
00770     DataRangefinderTimings(const DataRangefinderTimings &other);
00771 
00772     static DataRangefinderTimings *popNext();
00773 
00774     static DataRangefinderTimings *waitNext(double timeout = 0);
00775 
00776     static DataRangefinderTimings *getUpdate(double timeout = 0);
00777 
00778     static void subscribe(uint16_t freq);
00779 
00780     static enum MessageTypes getTypeID();
00781 
00782     uint8_t getRangefinderCount();
00783 
00784     double getDistance(int rangefinder);
00785 
00786     uint32_t getAcquisitionTime(int rangefinder);
00787 
00788     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00789   };
00790 
00791   class DataRawAcceleration : public Message
00792   {
00793   public:
00794     enum payloadOffsets
00795     {
00796       X = 0,
00797       Y = 2,
00798       Z = 4,
00799       PAYLOAD_LEN = 6
00800     };
00801   public:
00802     DataRawAcceleration(void *input, size_t msg_len);
00803 
00804     DataRawAcceleration(const DataRawAcceleration &other);
00805 
00806     static DataRawAcceleration *popNext();
00807 
00808     static DataRawAcceleration *waitNext(double timeout = 0);
00809 
00810     static DataRawAcceleration *getUpdate(double timeout = 0);
00811 
00812     static void subscribe(uint16_t freq);
00813 
00814     static enum MessageTypes getTypeID();
00815 
00816     uint16_t getX();
00817 
00818     uint16_t getY();
00819 
00820     uint16_t getZ();
00821 
00822     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00823   };
00824 
00825   class Data6AxisYaw : public Message
00826   {
00827   public:
00828     enum payloadOffsets{
00829       Angle = 0,
00830       Angle_rate = 2,
00831       PAYLOAD_LEN = 4
00832     };
00833   public:
00834     Data6AxisYaw(void *input, size_t msg_len);
00835     
00836     Data6AxisYaw(const Data6AxisYaw &other);
00837     
00838     static Data6AxisYaw *popNext();
00839 
00840     static Data6AxisYaw *waitNext(double timeout = 0);
00841 
00842     static Data6AxisYaw *getUpdate(double timeout = 0);
00843 
00844     static void subscribe(uint16_t freq);
00845 
00846     static enum MessageTypes getTypeID();
00847     
00848     double getAngle();
00849     
00850     double getAngleRate();
00851     
00852     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00853   };
00854   
00855   class DataRawCurrent : public Message
00856   {
00857   public:
00858     DataRawCurrent(void *input, size_t msg_len);
00859 
00860     DataRawCurrent(const DataRawCurrent &other);
00861 
00862     static DataRawCurrent *popNext();
00863 
00864     static DataRawCurrent *waitNext(double timeout = 0);
00865 
00866     static DataRawCurrent *getUpdate(double timeout = 0);
00867 
00868     static void subscribe(uint16_t freq);
00869 
00870     static enum MessageTypes getTypeID();
00871 
00872     uint8_t getCurrentCount();
00873 
00874     uint16_t getCurrent(int current);
00875 
00876     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00877   };
00878 
00879   class DataRawGyro : public Message
00880   {
00881   public:
00882     enum payloadOffsets
00883     {
00884       ROLL = 0,
00885       PITCH = 2,
00886       YAW = 4,
00887       PAYLOAD_LEN = 6
00888     };
00889   public:
00890     DataRawGyro(void *input, size_t msg_len);
00891 
00892     DataRawGyro(const DataRawGyro &other);
00893 
00894     static DataRawGyro *popNext();
00895 
00896     static DataRawGyro *waitNext(double timeout = 0);
00897 
00898     static DataRawGyro *getUpdate(double timeout = 0);
00899 
00900     static void subscribe(uint16_t freq);
00901 
00902     static enum MessageTypes getTypeID();
00903 
00904     uint16_t getRoll();
00905 
00906     uint16_t getPitch();
00907 
00908     uint16_t getYaw();
00909 
00910     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00911   };
00912 
00913   class DataRawMagnetometer : public Message
00914   {
00915   public:
00916     enum payloadOffsets
00917     {
00918       X = 0,
00919       Y = 2,
00920       Z = 4,
00921       PAYLOAD_LEN = 6
00922     };
00923   public:
00924     DataRawMagnetometer(void *input, size_t msg_len);
00925 
00926     DataRawMagnetometer(const DataRawMagnetometer &other);
00927 
00928     static DataRawMagnetometer *popNext();
00929 
00930     static DataRawMagnetometer *waitNext(double timeout = 0);
00931 
00932     static DataRawMagnetometer *getUpdate(double timeout = 0);
00933 
00934     static void subscribe(uint16_t freq);
00935 
00936     static enum MessageTypes getTypeID();
00937 
00938     uint16_t getX();
00939 
00940     uint16_t getY();
00941 
00942     uint16_t getZ();
00943 
00944     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
00945   };
00946 
00947   class DataXYZData : public Message
00948   {
00949   public:
00950     enum payloadOffsets
00951     {
00952       X_DISTENCE = 0,
00953       Y_DISTENCE = 4,
00954       Z_RADIAN = 8,
00955       PAYLOAD_LEN = 10
00956     };
00957   public:
00958     DataXYZData(void *input, size_t msg_len);
00959 
00960     DataXYZData(const DataXYZData &other);
00961 
00962     static DataXYZData *popNext();
00963 
00964     static DataXYZData *waitNext(double timeout = 0);
00965 
00966     static DataXYZData *getUpdate(double timeout = 0);
00967 
00968     static void subscribe(uint16_t freq);
00969 
00970     static enum MessageTypes getTypeID();
00971 
00972     double getXDistence();
00973 
00974     double getYDistence();
00975 
00976     double getZRadian();
00977 
00978     virtual std::ostream &printMessage(std::ostream &stream = std::cout);    
00979   };
00980 
00981   class DataRawOrientation : public Message
00982   {
00983   public:
00984     enum payloadOffsets
00985     {
00986       ROLL = 0,
00987       PITCH = 2,
00988       YAW = 4,
00989       PAYLOAD_LEN = 6
00990     };
00991   public:
00992     DataRawOrientation(void *input, size_t msg_len);
00993 
00994     DataRawOrientation(const DataRawOrientation &other);
00995 
00996     static DataRawOrientation *popNext();
00997 
00998     static DataRawOrientation *waitNext(double timeout = 0);
00999 
01000     static DataRawOrientation *getUpdate(double timeout = 0);
01001 
01002     static void subscribe(uint16_t freq);
01003 
01004     static enum MessageTypes getTypeID();
01005 
01006     uint16_t getRoll();
01007 
01008     uint16_t getPitch();
01009 
01010     uint16_t getYaw();
01011 
01012     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01013   };
01014 
01015   class DataRawTemperature : public Message
01016   {
01017   public:
01018     DataRawTemperature(void *input, size_t msg_len);
01019 
01020     DataRawTemperature(const DataRawTemperature &other);
01021 
01022     static DataRawTemperature *popNext();
01023 
01024     static DataRawTemperature *waitNext(double timeout = 0);
01025 
01026     static DataRawTemperature *getUpdate(double timeout = 0);
01027 
01028     static void subscribe(uint16_t freq);
01029 
01030     static enum MessageTypes getTypeID();
01031 
01032     uint8_t getTemperatureCount();
01033 
01034     uint16_t getTemperature(int temperature);
01035 
01036     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01037   };
01038 
01039   class DataRawVoltage : public Message
01040   {
01041   public:
01042     DataRawVoltage(void *input, size_t msg_len);
01043 
01044     DataRawVoltage(const DataRawVoltage &other);
01045 
01046     static DataRawVoltage *popNext();
01047 
01048     static DataRawVoltage *waitNext(double timeout = 0);
01049 
01050     static DataRawVoltage *getUpdate(double timeout = 0);
01051 
01052     static void subscribe(uint16_t freq);
01053 
01054     static enum MessageTypes getTypeID();
01055 
01056     uint8_t getVoltageCount();
01057 
01058     uint16_t getVoltage(int temperature);
01059 
01060     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01061   };
01062 
01063   class DataSafetySystemStatus : public Message
01064   {
01065   public:
01066     DataSafetySystemStatus(void *input, size_t msg_len);
01067 
01068     DataSafetySystemStatus(const DataSafetySystemStatus &other);
01069 
01070     static DataSafetySystemStatus *popNext();
01071 
01072     static DataSafetySystemStatus *waitNext(double timeout = 0);
01073 
01074     static DataSafetySystemStatus *getUpdate(double timeout = 0);
01075 
01076     static void subscribe(uint16_t freq);
01077 
01078     static enum MessageTypes getTypeID();
01079 
01080     uint16_t getFlags();
01081 
01082     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01083   };
01084 
01085   class DataSystemStatus : public Message
01086   {
01087   private:
01088     uint8_t voltages_offset;
01089     uint8_t currents_offset;
01090     uint8_t temperatures_offset;
01091 
01092   public:
01093     DataSystemStatus(void *input, size_t msg_len);
01094 
01095     DataSystemStatus(const DataSystemStatus &other);
01096 
01097     static DataSystemStatus *popNext();
01098 
01099     static DataSystemStatus *waitNext(double timeout = 0);
01100 
01101     static DataSystemStatus *getUpdate(double timeout = 0);
01102 
01103     static void subscribe(uint16_t freq);
01104 
01105     static enum MessageTypes getTypeID();
01106 
01107     uint32_t getUptime();
01108 
01109     uint8_t getVoltagesCount();
01110 
01111     double getVoltage(uint8_t index);
01112 
01113     uint8_t getCurrentsCount();
01114 
01115     double getCurrent(uint8_t index);
01116 
01117     uint8_t getTemperaturesCount();
01118 
01119     double getTemperature(uint8_t index);
01120 
01121     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01122   };
01123 
01124   class DataVelocity : public Message
01125   {
01126   public:
01127     enum payloadOffsets
01128     {
01129       TRANS_VEL = 0,
01130       ROTATIONAL = 2,
01131       TRANS_ACCEL = 4,
01132       PAYLOAD_LEN = 6
01133     };
01134   public:
01135     DataVelocity(void *input, size_t msg_len);
01136 
01137     DataVelocity(const DataVelocity &other);
01138 
01139     static DataVelocity *popNext();
01140 
01141     static DataVelocity *waitNext(double timeout = 0);
01142 
01143     static DataVelocity *getUpdate(double timeout = 0);
01144 
01145     static void subscribe(uint16_t freq);
01146 
01147     static enum MessageTypes getTypeID();
01148 
01149     double getTranslational();
01150 
01151     double getRotational();
01152 
01153     double getTransAccel();
01154 
01155     virtual std::ostream &printMessage(std::ostream &stream = std::cout);
01156   };
01157 
01158 }; // namespace sawyer
01159 
01160 #endif  // sawyer_MESSAGE_DATA_H
01161 


roch_base
Author(s): Mike Purvis , Paul Bovbel , Carl
autogenerated on Sat Jun 8 2019 20:32:33