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