Message_data.h
Go to the documentation of this file.
1 
38 #ifndef SAWYER_MESSAGE_DATA_H
39 #define SAWYER_MESSAGE_DATA_H
40 
41 #include <iostream>
42 #include <string>
43 #include <stdint.h>
44 #include "roch_base/core/Message.h"
46 #include <boost/concept_check.hpp>
47 
48 namespace sawyer
49 {
50 
52  {
53  public:
55  {
56  STEERING = 0,
57  THROTTLE = 2,
58  BRAKE = 4,
60  };
61  public:
62  DataAckermannOutput(void *input, size_t msg_len);
63 
65 
66  static DataAckermannOutput *popNext();
67 
68  static DataAckermannOutput *waitNext(double timeout = 0);
69 
70  static DataAckermannOutput *getUpdate(double timeout = 0);
71 
72  static void subscribe(uint16_t freq = 0);
73 
74  static enum MessageTypes getTypeID();
75 
76  double getSteering();
77 
78  double getThrottle();
79 
80  double getBrake();
81 
82  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
83  };
84 
86  {
87  public:
89  {
90  LEFT_P = 0,
91  LEFT_I = 2,
92  LEFT_D = 4,
93  RIGHT_P = 6,
94  RIGHT_I = 8,
95  RIGHT_D = 10,
97  };
98 
99  public:
100  DataDifferentialControl(void *input, size_t msg_len);
101 
103 
105 
106  static DataDifferentialControl *waitNext(double timeout = 0);
107 
108  static DataDifferentialControl *getUpdate(double timeout = 0);
109 
110  static void subscribe(uint16_t freq = 0);
111 
112  static enum MessageTypes getTypeID();
113 
114  double getLeftP();
115 
116  double getLeftI();
117 
118  double getLeftD();
119 
120  double getRightP();
121 
122  double getRightI();
123 
124  double getRightD();
125 
126  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
127  };
128 
130  {
131  public:
133  {
134  LEFT = 0,
135  RIGHT = 2,
137  };
138 
139  public:
140  DataDifferentialOutput(void *input, size_t msg_len);
141 
143 
145 
146  static DataDifferentialOutput *waitNext(double timeout = 0);
147 
148  static DataDifferentialOutput *getUpdate(double timeout = 0);
149 
150  static void subscribe(uint16_t freq);
151 
152  static enum MessageTypes getTypeID();
153 
154  double getLeft();
155 
156  double getRight();
157 
158  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
159  };
160 
162  {
163  public:
165  {
166  LEFT_SPEED = 0,
167  RIGHT_SPEED = 2,
168  LEFT_ACCEL = 4,
169  RIGHT_ACCEL = 6,
171  };
172 
173  public:
174  DataDifferentialSpeed(void *input, size_t msg_len);
175 
177 
178  static DataDifferentialSpeed *popNext();
179 
180  static DataDifferentialSpeed *waitNext(double timeout = 0);
181 
182  static DataDifferentialSpeed *getUpdate(double timeout = 0);
183 
184  static void subscribe(uint16_t freq);
185 
186  static enum MessageTypes getTypeID();
187 
188  double getLeftSpeed();
189 
190  double getLeftAccel();
191 
192  double getRightSpeed();
193 
194  double getRightAccel();
195 
196  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
197  };
198 
199  class DataWheelInfo : public Message
200  {
201  public:
203  {
204  WHEEL_GAUGE = 0,
205  WHEEL_DIAMETER = 2,
207  };
208 
209  public:
210  DataWheelInfo(void *input, size_t msg_len);
211 
212  DataWheelInfo(const DataWheelInfo &other);
213 
214  static DataWheelInfo *popNext();
215 
216  static DataWheelInfo *waitNext(double timeout = 0);
217 
218  static DataWheelInfo *getUpdate(double timeout = 0);
219 
220  static void subscribe(uint16_t freq);
221 
222  static enum MessageTypes getTypeID();
223 
224  double getWheelGauge();
225 
226  double getWheelDiameter();
227 
228  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
229  };
230 
231  class DataEcho : public Message
232  {
233  public:
234  DataEcho(void *input, size_t msg_len);
235 
236  DataEcho(const DataEcho &other);
237 
238  static DataEcho *popNext();
239 
240  static DataEcho *waitNext(double timeout = 0);
241 
242  static DataEcho *getUpdate(double timeout = 0);
243 
244  static void subscribe(uint16_t freq);
245 
246  static enum MessageTypes getTypeID();
247 
248  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
249  };
250 
251  class DataEncoders : public Message
252  {
253  private:
256 
257  public:
258  DataEncoders(void *input, size_t msg_len);
259 
260  DataEncoders(const DataEncoders &other);
261 
262  static DataEncoders *popNext();
263 
264  static DataEncoders *waitNext(double timeout = 0);
265 
266  static DataEncoders *getUpdate(double timeout = 0);
267 
268  static void subscribe(uint16_t freq);
269 
270  static enum MessageTypes getTypeID();
271 
272  uint8_t getCount();
273 
274  double getTravel(uint8_t index);
275 
276  double getSpeed(uint8_t index);
277 
278  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
279  };
280 
281  class DataEncodersRaw : public Message
282  {
283  public:
284  DataEncodersRaw(void *input, size_t pkt_len);
285 
286  DataEncodersRaw(const DataEncodersRaw &other);
287 
288  static DataEncodersRaw *popNext();
289 
290  static DataEncodersRaw *waitNext(double timeout = 0);
291 
292  static DataEncodersRaw *getUpdate(double timeout = 0);
293 
294  static void subscribe(uint16_t freq);
295 
296  static enum MessageTypes getTypeID();
297 
298  uint8_t getCount();
299 
300  int32_t getTicks(uint8_t inx);
301 
302  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
303  };
304 
305  class DataFirmwareInfo : public Message
306  {
307  public:
309  {
310  MAJOR_FIRM_VER = 0,
316  };
317 
318  class WriteTime
319  {
320  public:
321  uint32_t rawTime;
322  public:
323  WriteTime(uint32_t time) : rawTime(time)
324  {
325  }
326 
327  uint8_t minute()
328  {
329  return (rawTime) & 0x3f;
330  }
331 
332  uint8_t hour()
333  {
334  return (rawTime >> 6) & 0x1f;
335  }
336 
337  uint8_t day()
338  {
339  return (rawTime >> 11) & 0x3f;
340  }
341 
342  uint8_t month()
343  {
344  return (rawTime >> 17) & 0x0f;
345  }
346 
347  uint8_t year()
348  {
349  return (rawTime >> 21) & 0x7f;
350  }
351  };
352 
353  public:
354  DataFirmwareInfo(void *input, size_t msg_len);
355 
356  DataFirmwareInfo(const DataFirmwareInfo &other);
357 
358  static DataFirmwareInfo *popNext();
359 
360  static DataFirmwareInfo *waitNext(double timeout = 0);
361 
362  static DataFirmwareInfo *getUpdate(double timeout = 0);
363 
364  static void subscribe(uint16_t freq);
365 
366  static enum MessageTypes getTypeID();
367 
368  uint8_t getMajorFirmwareVersion();
369 
370  uint8_t getMinorFirmwareVersion();
371 
372  uint8_t getMajorProtocolVersion();
373 
374  uint8_t getMinorProtocolVersion();
375 
376  WriteTime getWriteTime();
377 
378  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
379  };
380 
381  class DataGear : public Message
382  {
383  public:
384  DataGear(void *input, size_t msg_len);
385 
386  DataGear(const DataGear &other);
387 
388  static DataGear *popNext();
389 
390  static DataGear *waitNext(double timeout = 0);
391 
392  static DataGear *getUpdate(double timeout = 0);
393 
394  static void subscribe(uint16_t freq);
395 
396  static enum MessageTypes getTypeID();
397 
398  uint8_t getGear();
399 
400  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
401  };
402 
404  {
405  public:
407  {
408  FORWARD_MAX = 0,
409  REVERSE_MAX = 2,
411  };
412 
413  public:
414  DataMaxAcceleration(void *input, size_t msg_len);
415 
417 
418  static DataMaxAcceleration *popNext();
419 
420  static DataMaxAcceleration *waitNext(double timeout = 0);
421 
422  static DataMaxAcceleration *getUpdate(double timeout = 0);
423 
424  static void subscribe(uint16_t freq);
425 
426  static enum MessageTypes getTypeID();
427 
428  double getForwardMax();
429 
430  double getReverseMax();
431 
432  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
433  };
434 
435  class DataMaxSpeed : public Message
436  {
437  public:
439  {
440  FORWARD_MAX = 0,
441  REVERSE_MAX = 2,
443  };
444 
445  public:
446  DataMaxSpeed(void *input, size_t msg_len);
447 
448  DataMaxSpeed(const DataMaxSpeed &other);
449 
450  static DataMaxSpeed *popNext();
451 
452  static DataMaxSpeed *waitNext(double timeout = 0);
453 
454  static DataMaxSpeed *getUpdate(double timeout = 0);
455 
456  static void subscribe(uint16_t freq);
457 
458  static enum MessageTypes getTypeID();
459 
460  double getForwardMax();
461 
462  double getReverseMax();
463 
464  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
465  };
466 
468  {
469  public:
471  {
472  X = 0,
473  Y = 2,
474  Z = 4,
476  };
477  public:
478  DataPlatformAcceleration(void *input, size_t msg_len);
479 
481 
483 
484  static DataPlatformAcceleration *waitNext(double timeout = 0);
485 
486  static DataPlatformAcceleration *getUpdate(double timeout = 0);
487 
488  static void subscribe(uint16_t freq = 0);
489 
490  static enum MessageTypes getTypeID();
491 
492  double getX();
493 
494  double getY();
495 
496  double getZ();
497 
498  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
499  };
500 
501  class DataPlatformInfo : public Message
502  {
503  private:
504  uint8_t strlenModel();
505 
506  public:
507  DataPlatformInfo(void *input, size_t msg_len);
508 
509  DataPlatformInfo(const DataPlatformInfo &other);
510 
511  static DataPlatformInfo *popNext();
512 
513  static DataPlatformInfo *waitNext(double timeout = 0);
514 
515  static DataPlatformInfo *getUpdate(double timeout = 0);
516 
517  static void subscribe(uint16_t freq);
518 
519  static enum MessageTypes getTypeID();
520 
521  std::string getModel();
522 
523  uint8_t getRevision();
524 
525  uint32_t getSerial();
526 
527  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
528  };
529 
530  class DataPlatformName : public Message
531  {
532  public:
533  DataPlatformName(void *input, size_t msg_len);
534 
535  DataPlatformName(const DataPlatformName &other);
536 
537  static DataPlatformName *popNext();
538 
539  static DataPlatformName *waitNext(double timeout = 0);
540 
541  static DataPlatformName *getUpdate(double timeout = 0);
542 
543  static void subscribe(uint16_t freq);
544 
545  static enum MessageTypes getTypeID();
546 
547  std::string getName();
548 
549  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
550  };
551 
553  {
554  public:
556  {
557  X = 0,
558  Y = 2,
559  Z = 4,
561  };
562  public:
563  DataPlatformMagnetometer(void *input, size_t msg_len);
564 
566 
568 
569  static DataPlatformMagnetometer *waitNext(double timeout = 0);
570 
571  static DataPlatformMagnetometer *getUpdate(double timeout = 0);
572 
573  static void subscribe(uint16_t freq);
574 
575  static enum MessageTypes getTypeID();
576 
577  double getX();
578 
579  double getY();
580 
581  double getZ();
582 
583  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
584  };
585 
587  {
588  public:
590  {
591  ROLL = 0,
592  PITCH = 2,
593  YAW = 4,
595  };
596  public:
597  DataPlatformOrientation(void *input, size_t msg_len);
598 
600 
602 
603  static DataPlatformOrientation *waitNext(double timeout = 0);
604 
605  static DataPlatformOrientation *getUpdate(double timeout = 0);
606 
607  static void subscribe(uint16_t freq);
608 
609  static enum MessageTypes getTypeID();
610 
611  double getRoll();
612 
613  double getYaw();
614 
615  double getPitch();
616 
617  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
618  };
619 
621  {
622  public:
624  {
625  ROLL_RATE = 0,
626  PITCH_RATE = 2,
627  YAW_RATE = 4,
629  };
630 
631  public:
632  DataPlatformRotation(void *input, size_t msg_len);
633 
635 
636  static DataPlatformRotation *popNext();
637 
638  static DataPlatformRotation *waitNext(double timeout = 0);
639 
640  static DataPlatformRotation *getUpdate(double timeout = 0);
641 
642  static void subscribe(uint16_t freq);
643 
644  static enum MessageTypes getTypeID();
645 
646  double getRollRate();
647 
648  double getPitchRate();
649 
650  double getYawRate();
651 
652  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
653  };
654 
655  class DataPowerSystem : public Message
656  {
657  public:
659  {
660  public:
661  enum Types
662  {
663  EXTERNAL = 0x0,
664  LEAD_ACID = 0x1,
665  NIMH = 0x2,
666  Li_ion = 0x3,
667  GASOLINE = 0x8
668  };
669  uint8_t rawDesc;
670  public:
671  BatteryDescription(uint8_t desc) : rawDesc(desc)
672  {
673  }
674 
675  bool isPresent()
676  {
677  return rawDesc & 0x80;
678  }
679 
680  bool isInUse()
681  {
682  return rawDesc & 0x40;
683  }
684 
685  enum Types getType()
686  {
687  return (enum Types) (rawDesc & 0x0f);
688  }
689  };
690 
691  public:
692  DataPowerSystem(void *input, size_t msg_len);
693 
694  DataPowerSystem(const DataPowerSystem &other);
695 
696  static DataPowerSystem *popNext();
697 
698  static DataPowerSystem *waitNext(double timeout = 0);
699 
700  static DataPowerSystem *getUpdate(double timeout = 0);
701 
702  static void subscribe(uint16_t freq);
703 
704  static enum MessageTypes getTypeID();
705 
706  uint8_t getBatteryCount();
707 
708  double getChargeEstimate(uint8_t battery);
709 
710  int16_t getCapacityEstimate(uint8_t battery);
711 
712  BatteryDescription getDescription(uint8_t battery);
713 
714  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
715  };
716 
718  {
719  public:
720  DataProcessorStatus(void *input, size_t msg_len);
721 
723 
724  static DataProcessorStatus *popNext();
725 
726  static DataProcessorStatus *waitNext(double timeout = 0);
727 
728  static DataProcessorStatus *getUpdate(double timeout = 0);
729 
730  static void subscribe(uint16_t freq);
731 
732  static enum MessageTypes getTypeID();
733 
734  uint8_t getProcessCount();
735 
736  int16_t getErrorCount(int process);
737 
738  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
739  };
740 
741  class DataRangefinders : public Message
742  {
743  public:
744  DataRangefinders(void *input, size_t msg_len);
745 
746  DataRangefinders(const DataRangefinders &other);
747 
748  static DataRangefinders *popNext();
749 
750  static DataRangefinders *waitNext(double timeout = 0);
751 
752  static DataRangefinders *getUpdate(double timeout = 0);
753 
754  static void subscribe(uint16_t freq);
755 
756  static enum MessageTypes getTypeID();
757 
758  uint8_t getRangefinderCount();
759 
760  double getDistance(int rangefinder);
761 
762  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
763  };
764 
766  {
767  public:
768  DataRangefinderTimings(void *input, size_t msg_len);
769 
771 
773 
774  static DataRangefinderTimings *waitNext(double timeout = 0);
775 
776  static DataRangefinderTimings *getUpdate(double timeout = 0);
777 
778  static void subscribe(uint16_t freq);
779 
780  static enum MessageTypes getTypeID();
781 
782  uint8_t getRangefinderCount();
783 
784  double getDistance(int rangefinder);
785 
786  uint32_t getAcquisitionTime(int rangefinder);
787 
788  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
789  };
790 
792  {
793  public:
795  {
796  X = 0,
797  Y = 2,
798  Z = 4,
800  };
801  public:
802  DataRawAcceleration(void *input, size_t msg_len);
803 
805 
806  static DataRawAcceleration *popNext();
807 
808  static DataRawAcceleration *waitNext(double timeout = 0);
809 
810  static DataRawAcceleration *getUpdate(double timeout = 0);
811 
812  static void subscribe(uint16_t freq);
813 
814  static enum MessageTypes getTypeID();
815 
816  uint16_t getX();
817 
818  uint16_t getY();
819 
820  uint16_t getZ();
821 
822  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
823  };
824 
825  class Data6AxisYaw : public Message
826  {
827  public:
829  Angle = 0,
830  Angle_rate = 2,
832  };
833  public:
834  Data6AxisYaw(void *input, size_t msg_len);
835 
836  Data6AxisYaw(const Data6AxisYaw &other);
837 
838  static Data6AxisYaw *popNext();
839 
840  static Data6AxisYaw *waitNext(double timeout = 0);
841 
842  static Data6AxisYaw *getUpdate(double timeout = 0);
843 
844  static void subscribe(uint16_t freq);
845 
846  static enum MessageTypes getTypeID();
847 
848  double getAngle();
849 
850  double getAngleRate();
851 
852  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
853  };
854 
855  class DataRawCurrent : public Message
856  {
857  public:
858  DataRawCurrent(void *input, size_t msg_len);
859 
860  DataRawCurrent(const DataRawCurrent &other);
861 
862  static DataRawCurrent *popNext();
863 
864  static DataRawCurrent *waitNext(double timeout = 0);
865 
866  static DataRawCurrent *getUpdate(double timeout = 0);
867 
868  static void subscribe(uint16_t freq);
869 
870  static enum MessageTypes getTypeID();
871 
872  uint8_t getCurrentCount();
873 
874  uint16_t getCurrent(int current);
875 
876  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
877  };
878 
879  class DataRawGyro : public Message
880  {
881  public:
883  {
884  ROLL = 0,
885  PITCH = 2,
886  YAW = 4,
888  };
889  public:
890  DataRawGyro(void *input, size_t msg_len);
891 
892  DataRawGyro(const DataRawGyro &other);
893 
894  static DataRawGyro *popNext();
895 
896  static DataRawGyro *waitNext(double timeout = 0);
897 
898  static DataRawGyro *getUpdate(double timeout = 0);
899 
900  static void subscribe(uint16_t freq);
901 
902  static enum MessageTypes getTypeID();
903 
904  uint16_t getRoll();
905 
906  uint16_t getPitch();
907 
908  uint16_t getYaw();
909 
910  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
911  };
912 
914  {
915  public:
917  {
918  X = 0,
919  Y = 2,
920  Z = 4,
922  };
923  public:
924  DataRawMagnetometer(void *input, size_t msg_len);
925 
927 
928  static DataRawMagnetometer *popNext();
929 
930  static DataRawMagnetometer *waitNext(double timeout = 0);
931 
932  static DataRawMagnetometer *getUpdate(double timeout = 0);
933 
934  static void subscribe(uint16_t freq);
935 
936  static enum MessageTypes getTypeID();
937 
938  uint16_t getX();
939 
940  uint16_t getY();
941 
942  uint16_t getZ();
943 
944  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
945  };
946 
947  class DataXYZData : public Message
948  {
949  public:
951  {
952  X_DISTENCE = 0,
953  Y_DISTENCE = 4,
954  Z_RADIAN = 8,
956  };
957  public:
958  DataXYZData(void *input, size_t msg_len);
959 
960  DataXYZData(const DataXYZData &other);
961 
962  static DataXYZData *popNext();
963 
964  static DataXYZData *waitNext(double timeout = 0);
965 
966  static DataXYZData *getUpdate(double timeout = 0);
967 
968  static void subscribe(uint16_t freq);
969 
970  static enum MessageTypes getTypeID();
971 
972  double getXDistence();
973 
974  double getYDistence();
975 
976  double getZRadian();
977 
978  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
979  };
980 
982  {
983  public:
985  {
986  ROLL = 0,
987  PITCH = 2,
988  YAW = 4,
990  };
991  public:
992  DataRawOrientation(void *input, size_t msg_len);
993 
995 
996  static DataRawOrientation *popNext();
997 
998  static DataRawOrientation *waitNext(double timeout = 0);
999 
1000  static DataRawOrientation *getUpdate(double timeout = 0);
1001 
1002  static void subscribe(uint16_t freq);
1003 
1004  static enum MessageTypes getTypeID();
1005 
1006  uint16_t getRoll();
1007 
1008  uint16_t getPitch();
1009 
1010  uint16_t getYaw();
1011 
1012  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1013  };
1014 
1016  {
1017  public:
1018  DataRawTemperature(void *input, size_t msg_len);
1019 
1020  DataRawTemperature(const DataRawTemperature &other);
1021 
1022  static DataRawTemperature *popNext();
1023 
1024  static DataRawTemperature *waitNext(double timeout = 0);
1025 
1026  static DataRawTemperature *getUpdate(double timeout = 0);
1027 
1028  static void subscribe(uint16_t freq);
1029 
1030  static enum MessageTypes getTypeID();
1031 
1032  uint8_t getTemperatureCount();
1033 
1034  uint16_t getTemperature(int temperature);
1035 
1036  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1037  };
1038 
1039  class DataRawVoltage : public Message
1040  {
1041  public:
1042  DataRawVoltage(void *input, size_t msg_len);
1043 
1044  DataRawVoltage(const DataRawVoltage &other);
1045 
1046  static DataRawVoltage *popNext();
1047 
1048  static DataRawVoltage *waitNext(double timeout = 0);
1049 
1050  static DataRawVoltage *getUpdate(double timeout = 0);
1051 
1052  static void subscribe(uint16_t freq);
1053 
1054  static enum MessageTypes getTypeID();
1055 
1056  uint8_t getVoltageCount();
1057 
1058  uint16_t getVoltage(int temperature);
1059 
1060  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1061  };
1062 
1064  {
1065  public:
1066  DataSafetySystemStatus(void *input, size_t msg_len);
1067 
1069 
1070  static DataSafetySystemStatus *popNext();
1071 
1072  static DataSafetySystemStatus *waitNext(double timeout = 0);
1073 
1074  static DataSafetySystemStatus *getUpdate(double timeout = 0);
1075 
1076  static void subscribe(uint16_t freq);
1077 
1078  static enum MessageTypes getTypeID();
1079 
1080  uint16_t getFlags();
1081 
1082  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1083  };
1084 
1085  class DataSystemStatus : public Message
1086  {
1087  private:
1091 
1092  public:
1093  DataSystemStatus(void *input, size_t msg_len);
1094 
1095  DataSystemStatus(const DataSystemStatus &other);
1096 
1097  static DataSystemStatus *popNext();
1098 
1099  static DataSystemStatus *waitNext(double timeout = 0);
1100 
1101  static DataSystemStatus *getUpdate(double timeout = 0);
1102 
1103  static void subscribe(uint16_t freq);
1104 
1105  static enum MessageTypes getTypeID();
1106 
1107  uint32_t getUptime();
1108 
1109  uint8_t getVoltagesCount();
1110 
1111  double getVoltage(uint8_t index);
1112 
1113  uint8_t getCurrentsCount();
1114 
1115  double getCurrent(uint8_t index);
1116 
1117  uint8_t getTemperaturesCount();
1118 
1119  double getTemperature(uint8_t index);
1120 
1121  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1122  };
1123 
1124  class DataVelocity : public Message
1125  {
1126  public:
1128  {
1129  TRANS_VEL = 0,
1130  ROTATIONAL = 2,
1131  TRANS_ACCEL = 4,
1133  };
1134  public:
1135  DataVelocity(void *input, size_t msg_len);
1136 
1137  DataVelocity(const DataVelocity &other);
1138 
1139  static DataVelocity *popNext();
1140 
1141  static DataVelocity *waitNext(double timeout = 0);
1142 
1143  static DataVelocity *getUpdate(double timeout = 0);
1144 
1145  static void subscribe(uint16_t freq);
1146 
1147  static enum MessageTypes getTypeID();
1148 
1149  double getTranslational();
1150 
1151  double getRotational();
1152 
1153  double getTransAccel();
1154 
1155  virtual std::ostream &printMessage(std::ostream &stream = std::cout);
1156  };
1157 
1158 }; // namespace sawyer
1159 
1160 #endif // sawyer_MESSAGE_DATA_H
1161 
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static void subscribe(uint16_t freq=0)
static DataAckermannOutput * popNext()
MessageTypes
Definition: Message.h:207
std::string getName(void *handle)
static enum MessageTypes getTypeID()
static DataAckermannOutput * getUpdate(double timeout=0)
uint16_t getType()
Definition: Message.cpp:243
double getYaw(const tf2::Quaternion quat)
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
DataAckermannOutput(void *input, size_t msg_len)
static DataAckermannOutput * waitNext(double timeout=0)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
uint8_t getFlags()
Definition: Message.cpp:238


roch_base
Author(s): Mike Purvis , Paul Bovbel , Chen
autogenerated on Mon Jun 10 2019 14:41:14