Message_data.cpp
Go to the documentation of this file.
4 
5 #include <iostream>
6 #include <string>
7 #include <string.h>
8 #include <sstream>
9 
10 using namespace std;
11 
12 namespace sawyer
13 {
14 
24 #define MESSAGE_CONSTRUCTORS(MessageClass, ExpectedLength) \
25 MessageClass::MessageClass(void* input, size_t msg_len) : Message(input, msg_len) \
26 { \
27  if( ((ExpectedLength) >= 0) && ((ssize_t)getPayloadLength() != (ExpectedLength)) ) { \
28  stringstream ss; \
29  ss << "Bad payload length: actual="<<getPayloadLength(); \
30  ss <<" vs. expected="<<(ExpectedLength); \
31  throw new MessageException(ss.str().c_str(), MessageException::INVALID_LENGTH); \
32  } \
33 } \
34 MessageClass::MessageClass(const MessageClass& other) : Message(other) {}
35 
36 
41 #define MESSAGE_CONVENIENCE_FNS(MessageClass, DataMsgID) \
42 MessageClass* MessageClass::popNext() { \
43  return dynamic_cast<MessageClass*>( Transport::instance().popNext(DataMsgID)); \
44 } \
45 \
46 MessageClass* MessageClass::waitNext(double timeout) { \
47 return dynamic_cast<MessageClass*>(Transport::instance().waitNext(DataMsgID, timeout)); \
48 } \
49 \
50 MessageClass* MessageClass::getUpdate(double timeout) { \
51  subscribe(0); \
52  return dynamic_cast<MessageClass*>( \
53  Transport::instance().waitNext(DataMsgID, timeout) ); \
54 }\
55 \
56 void MessageClass::subscribe(uint16_t freq) { \
57  Request(DataMsgID-0x4000, freq).sendRequest(); \
58 } \
59 \
60 enum MessageTypes MessageClass::getTypeID() { \
61  return DataMsgID; \
62 }
63  MESSAGE_CONSTRUCTORS(DataAckermannOutput, PAYLOAD_LEN)
64 
66 
67  double DataAckermannOutput::getSteering()
68  {
69  return btof(getPayloadPointer(STEERING), 2, 100);
70  }
71 
72  double DataAckermannOutput::getThrottle()
73  {
74  return btof(getPayloadPointer(THROTTLE), 2, 100);
75  }
76 
77  double DataAckermannOutput::getBrake()
78  {
79  return btof(getPayloadPointer(BRAKE), 2, 100);
80  }
81 
82  ostream &DataAckermannOutput::printMessage(ostream &stream)
83  {
84  stream << "Ackermann Control" << endl;
85  stream << "=================" << endl;
86  stream << "Steering: " << getSteering() << endl;
87  stream << "Throttle: " << getThrottle() << endl;
88  stream << "Brake : " << getBrake() << endl;
89  return stream;
90  }
91 
92 
93 
95 
97 
98  double DataDifferentialControl::getLeftP()
99  {
100  return btof(getPayloadPointer(LEFT_P), 2, 10000);
101  }
102 
103  double DataDifferentialControl::getLeftI()
104  {
105  return btof(getPayloadPointer(LEFT_I), 2, 10000);
106  }
107 
108  double DataDifferentialControl::getLeftD()
109  {
110  return btof(getPayloadPointer(LEFT_D), 2, 10000);
111  }
112 
113  double DataDifferentialControl::getRightP()
114  {
115  return btof(getPayloadPointer(RIGHT_P), 2, 10000);
116  }
117 
118  double DataDifferentialControl::getRightI()
119  {
120  return btof(getPayloadPointer(RIGHT_I), 2, 10000);
121  }
122 
123  double DataDifferentialControl::getRightD()
124  {
125  return btof(getPayloadPointer(RIGHT_D), 2, 10000);
126  }
127 
128  ostream &DataDifferentialControl::printMessage(ostream &stream)
129  {
130  stream << "Differential Control Constant Data" << endl;
131  stream << "==================================" << endl;
132  stream << "Left P : " << getLeftP() << endl;
133  stream << "Left I : " << getLeftI() << endl;
134  stream << "Left D : " << getLeftD() << endl;
135  stream << "Right P : " << getRightP() << endl;
136  stream << "Right I : " << getRightI() << endl;
137  stream << "Right D : " << getRightD() << endl;
138  return stream;
139  }
140 
141 
143 
145 
146  double DataDifferentialOutput::getLeft()
147  {
148  return btof(getPayloadPointer(LEFT), 2, 100);
149  }
150 
151  double DataDifferentialOutput::getRight()
152  {
153  return btof(getPayloadPointer(RIGHT), 2, 100);
154  }
155 
156  ostream &DataDifferentialOutput::printMessage(ostream &stream)
157  {
158  stream << "Differential Output Data" << endl;
159  stream << "========================" << endl;
160  stream << "Left : " << getLeft() << endl;
161  stream << "Right: " << getRight() << endl;
162  return stream;
163  }
164 
165 
166 
168 
170 
171  double DataDifferentialSpeed::getLeftSpeed()
172  {
173  return btof(getPayloadPointer(LEFT_SPEED), 2, 100);
174  }
175 
176  double DataDifferentialSpeed::getLeftAccel()
177  {
178  return btof(getPayloadPointer(LEFT_ACCEL), 2, 100);
179  }
180 
181  double DataDifferentialSpeed::getRightSpeed()
182  {
183  return btof(getPayloadPointer(RIGHT_SPEED), 2, 100);
184  }
185 
186  double DataDifferentialSpeed::getRightAccel()
187  {
188  return btof(getPayloadPointer(RIGHT_ACCEL), 2, 100);
189  }
190 
191  ostream &DataDifferentialSpeed::printMessage(ostream &stream)
192  {
193  stream << "Differential Speed Data" << endl;
194  stream << "=======================" << endl;
195  stream << "Left Speed : " << getLeftSpeed() << endl;
196  stream << "Left Accel : " << getLeftAccel() << endl;
197  stream << "Right Speed: " << getRightSpeed() << endl;
198  stream << "Right Accel: " << getRightAccel() << endl;
199  return stream;
200  }
201 
202 
203  MESSAGE_CONSTRUCTORS(DataWheelInfo, PAYLOAD_LEN);
204 
206 
207  double DataWheelInfo::getWheelGauge()
208  {
209  return btof(getPayloadPointer(WHEEL_GAUGE), 2, 10000);
210  }
211 
212  double DataWheelInfo::getWheelDiameter()
213  {
214  return btof(getPayloadPointer(WHEEL_DIAMETER), 2, 10000);
215  }
216 
217  ostream &DataWheelInfo::printMessage(ostream &stream)
218  {
219  stream << "Wheel Information" << endl;
220  stream << "=======================" << endl;
221  stream << "Wheel Gauge : " << getWheelGauge() << endl;
222  stream << "Wheel Diameter : " << getWheelDiameter() << endl;
223  return stream;
224  }
225 
227 
229 
230  ostream &DataEcho::printMessage(ostream &stream)
231  {
232  stream << "Echo!";
233  return stream;
234  }
235 
236 
237  DataEncoders::DataEncoders(void *input, size_t msg_len) : Message(input, msg_len)
238  {
239  if ((ssize_t) getPayloadLength() != (1 + getCount() * 6))
240  {
241  stringstream ss;
242  ss << "Bad payload length: actual=" << getPayloadLength();
243  ss << " vs. expected=" << (1 + getCount() * 6);
244  throw new MessageException(ss.str().c_str(), MessageException::INVALID_LENGTH);
245  }
246  travels_offset = 1;
247  speeds_offset = travels_offset + (getCount() * 4);
248  }
249 
251  {
252  }
253 
255 
257  {
258  return *getPayloadPointer(0);
259  }
260 
261  double DataEncoders::getTravel(uint8_t index)
262  {
263  return btof(getPayloadPointer(travels_offset + index * 4), 4, 1000);
264  }
265 
266  double DataEncoders::getSpeed(uint8_t index)
267  {
268  return btof(getPayloadPointer(speeds_offset + index * 2), 2, 1000);
269  }
270 
271  ostream &DataEncoders::printMessage(ostream &stream)
272  {
273  stream << "Encoder Data" << endl;
274  stream << "============" << endl;
275  stream << "Count : " << (int) (getCount()) << endl;
276  for (unsigned i = 0; i < getCount(); ++i)
277  {
278  stream << "Encoder " << i << ":" << endl;
279  stream << " Travel: " << getTravel(i) << endl;
280  stream << " Speed : " << getSpeed(i) << endl;
281  }
282  return stream;
283  }
284 
285 
286 
288 
290 
291  uint8_t DataEncodersRaw::getCount()
292  {
293  return *getPayloadPointer(0);
294  }
295 
296  int32_t DataEncodersRaw::getTicks(uint8_t inx)
297  {
298  return btoi(getPayloadPointer(1 + inx * 4), 4);
299  }
300 
301  ostream &DataEncodersRaw::printMessage(ostream &stream)
302  {
303  stream << "Raw Encoder Data" << endl;
304  stream << "================" << endl;
305  for (int i = 0; i < getCount(); ++i)
306  {
307  stream << "Encoder " << i << ": " << getTicks(i) << endl;
308  }
309  return stream;
310  }
311 
312 
313 
315 
317 
318  uint8_t DataFirmwareInfo::getMajorFirmwareVersion()
319  {
320  return *getPayloadPointer(MAJOR_FIRM_VER);
321  }
322 
324  {
325  return *getPayloadPointer(MINOR_FIRM_VER);
326  }
327 
329  {
330  return *getPayloadPointer(MAJOR_PROTO_VER);
331  }
332 
334  {
335  return *getPayloadPointer(MINOR_PROTO_VER);
336  }
337 
339  {
340  return WriteTime(btou(getPayloadPointer(WRITE_TIME), 4));
341  }
342 
343  ostream &DataFirmwareInfo::printMessage(ostream &stream)
344  {
345  stream << "Firmware Info" << endl;
346  stream << "=============" << endl;
347  stream << "Major firmware version: " << (int) getMajorFirmwareVersion() << endl;
348  stream << "Minor firmware version: " << (int) getMinorFirmwareVersion() << endl;
349  stream << "Major protocol version: " << (int) getMajorProtocolVersion() << endl;
350  stream << "Minor protocol version: " << (int) getMinorProtocolVersion() << endl;
351  WriteTime t = getWriteTime();
352  stream << "Firmware write time : ";
353  stream << (2000 + t.year()) << "-" << (int) t.month() << "-" << (int) t.day() << " ";
354  stream << (int) t.hour() << ":" << (int) t.minute() << endl;
355  return stream;
356  }
357 
358 
359 
361 
363 
364  uint8_t DataGear::getGear()
365  {
366  return getPayloadPointer()[0];
367  }
368 
369  ostream &DataGear::printMessage(ostream &stream)
370  {
371  stream << "Gear" << endl;
372  stream << "====" << endl;
373  stream << "Gear: " << (int) getGear() << endl;
374  return stream;
375  }
376 
377 
378 
380 
382 
383  double DataMaxAcceleration::getForwardMax()
384  {
385  return btof(getPayloadPointer(FORWARD_MAX), 2, 100);
386  }
387 
389  {
390  return btof(getPayloadPointer(REVERSE_MAX), 2, 100);
391  }
392 
393  ostream &DataMaxAcceleration::printMessage(ostream &stream)
394  {
395  stream << "Max Acceleration Data" << endl;
396  stream << "=====================" << endl;
397  stream << "Max Forward: " << getForwardMax() << endl;
398  stream << "Max Reverse: " << getReverseMax() << endl;
399  return stream;
400  }
401 
402 
403 
404  MESSAGE_CONSTRUCTORS(DataMaxSpeed, PAYLOAD_LEN)
405 
407 
408  double DataMaxSpeed::getForwardMax()
409  {
410  return btof(getPayloadPointer(FORWARD_MAX), 2, 100);
411  }
412 
414  {
415  return btof(getPayloadPointer(REVERSE_MAX), 2, 100);
416  }
417 
418  ostream &DataMaxSpeed::printMessage(ostream &stream)
419  {
420  stream << "Max Speed Data" << endl;
421  stream << "==============" << endl;
422  stream << "Max Forward: " << getForwardMax() << endl;
423  stream << "Max Reverse: " << getReverseMax() << endl;
424  return stream;
425  }
426 
427 
428 
430 
432 
434  {
435  return btof(getPayloadPointer(X), 2, 1000);
436  }
437 
439  {
440  return btof(getPayloadPointer(Y), 2, 1000);
441  }
442 
444  {
445  return btof(getPayloadPointer(Z), 2, 1000);
446  }
447 
448  ostream &DataPlatformAcceleration::printMessage(ostream &stream)
449  {
450  stream << "Platform Acceleration" << endl;
451  stream << "=====================" << endl;
452  stream << "X: " << getX() << endl;
453  stream << "Y: " << getY() << endl;
454  stream << "Z: " << getZ() << endl;
455  return stream;
456  }
457 
458 
459 
460  MESSAGE_CONSTRUCTORS(DataPlatformInfo, (int) strlenModel() + 6)
461 
463 
464  uint8_t DataPlatformInfo::strlenModel()
465  {
466  return *getPayloadPointer();
467  }
468 
470  {
471  char buf[256];
472  // NB: cpy_len cannot be larger than 255 (one byte field!)
473  size_t cpy_len = strlenModel();
474  memcpy(buf, getPayloadPointer(1), cpy_len);
475  buf[cpy_len] = '\0';
476 
477  return string(buf);
478  }
479 
481  {
482  char offset = strlenModel() + 1;
483  return *getPayloadPointer(offset);
484  }
485 
487  {
488  char offset = strlenModel() + 2;
489  return btou(getPayloadPointer(offset), 4);
490  }
491 
492  std::ostream &DataPlatformInfo::printMessage(std::ostream &stream)
493  {
494  stream << "Platform Info" << endl;
495  stream << "=============" << endl;
496  stream << "Model : " << getModel() << endl;
497  stream << "Revision: " << (int) (getRevision()) << endl;
498  stream << "Serial : " << getSerial() << endl;
499  return stream;
500  }
501 
502 
503 
505 
507 
508  string DataPlatformName::getName()
509  {
510  char buf[256];
511  size_t cpy_len = *getPayloadPointer();
512  memcpy(buf, getPayloadPointer(1), cpy_len);
513  buf[cpy_len] = '\0';
514  return string(buf);
515  }
516 
517  std::ostream &DataPlatformName::printMessage(std::ostream &stream)
518  {
519  stream << "Platform Name" << endl;
520  stream << "=============" << endl;
521  stream << "Name: " << getName() << endl;
522  return stream;
523  }
524 
525 
526 
528 
530 
532  {
533  return btof(getPayloadPointer(X), 2, 1000);
534  }
535 
537  {
538  return btof(getPayloadPointer(Y), 2, 1000);
539  }
540 
542  {
543  return btof(getPayloadPointer(Z), 2, 1000);
544  }
545 
546  ostream &DataPlatformMagnetometer::printMessage(ostream &stream)
547  {
548  stream << "PlatformMagnetometer Data" << endl;
549  stream << "=================" << endl;
550  stream << "X: " << getX() << endl;
551  stream << "Y: " << getY() << endl;
552  stream << "Z: " << getZ() << endl;
553  return stream;
554  }
555 
556 
557 
558  MESSAGE_CONSTRUCTORS(DataXYZData, PAYLOAD_LEN)
559 
561 
562  double DataXYZData::getXDistence()
563  {
564  return btof(getPayloadPointer(X_DISTENCE), 4, 1000);
565  }
566 
568  {
569  return btof(getPayloadPointer(Y_DISTENCE), 4, 1000);
570  }
571 
573  {
574  return btof(getPayloadPointer(Z_RADIAN), 4, 1000);
575  }
576 
577  ostream &DataXYZData::printMessage(ostream &stream)
578  {
579  stream << "Waypoints: X Y Z Data" << endl;
580  stream << "=================" << endl;
581  stream << "X: " << getXDistence() << endl;
582  stream << "Y: " << getYDistence() << endl;
583  stream << "Z: " << getZRadian() << endl;
584  return stream;
585  }
586 
587 
589 
591 
592  double DataPlatformOrientation::getRoll()
593  {
594  return btof(getPayloadPointer(ROLL), 2, 1000);
595  }
596 
598  {
599  return btof(getPayloadPointer(PITCH), 2, 1000);
600  }
601 
603  {
604  return btof(getPayloadPointer(YAW), 2, 1000);
605  }
606 
607  ostream &DataPlatformOrientation::printMessage(ostream &stream)
608  {
609  stream << "Platform Orientation" << endl;
610  stream << "====================" << endl;
611  stream << "Roll : " << getRoll() << endl;
612  stream << "Pitch: " << getPitch() << endl;
613  stream << "Yaw : " << getYaw() << endl;
614 
615  return stream;
616  }
617 
618 
619 
621 
623 
624  double DataPlatformRotation::getRollRate()
625  {
626  return btof(getPayloadPointer(ROLL_RATE), 2, 1000);
627  }
628 
630  {
631  return btof(getPayloadPointer(PITCH_RATE), 2, 1000);
632  }
633 
635  {
636  return btof(getPayloadPointer(YAW_RATE), 2, 1000);
637  }
638 
639  ostream &DataPlatformRotation::printMessage(ostream &stream)
640  {
641  stream << "Platform Rotationa Rate Data" << endl;
642  stream << "============================" << endl;
643  stream << "Roll : " << getRollRate() << endl;
644  stream << "Pitch: " << getPitchRate() << endl;
645  stream << "Yaw : " << getYawRate() << endl;
646  return stream;
647  }
648 
649 
650 
651  MESSAGE_CONSTRUCTORS(DataPowerSystem, 1 + getBatteryCount() * 5)
652 
654 
655  uint8_t DataPowerSystem::getBatteryCount()
656  {
657  return *getPayloadPointer(0);
658  }
659 
660  double DataPowerSystem::getChargeEstimate(uint8_t battery)
661  {
662  int offset = 1 /* num batteries */
663  + battery * 2;
664  return btof(getPayloadPointer(offset), 2, 100);
665  }
666 
667  int16_t DataPowerSystem::getCapacityEstimate(uint8_t battery)
668  {
669  int offset = 1 /* num batteries */
670  + 2 * getBatteryCount() /*charge estimate data*/
671  + battery * 2;
672  return btoi(getPayloadPointer(offset), 2);
673  }
674 
676  {
677  int offset = 1 /* num batteries */
678  + 4 * getBatteryCount() /* charge and capacity estimate data */
679  + battery;
680  return BatteryDescription(*getPayloadPointer(offset));
681  }
682 
683  ostream &DataPowerSystem::printMessage(ostream &stream)
684  {
685  stream << "Power System Status Data" << endl;
686  stream << "========================" << endl;
687  int num_bat = getBatteryCount();
688  stream << "Number of Batteries: " << num_bat << endl;
689  for (int i = 0; i < num_bat; ++i)
690  {
691  stream << "Battery " << i << ":" << endl;
692  stream << " Charge Estimate : " << getChargeEstimate(i) << endl;
693  stream << " Capacity Estimate: " << getCapacityEstimate(i) << endl;
694  stream << " Present : " << (getDescription(0).isPresent() ? "yes" : "no") << endl;
695  stream << " In Use : " << (getDescription(0).isInUse() ? "yes" : "no") << endl;
696  stream << " Type : ";
697  switch (getDescription(0).getType())
698  {
699  case BatteryDescription::EXTERNAL:
700  stream << "External" << endl;
701  break;
702  case BatteryDescription::LEAD_ACID:
703  stream << "Lead-Acid" << endl;
704  break;
705  case BatteryDescription::NIMH:
706  stream << "NiMH" << endl;
707  break;
708  case BatteryDescription::Li_ion:
709  stream << "Li_ion" << endl;
710  break;
711  case BatteryDescription::GASOLINE:
712  stream << "Internal Combustion Engine" << endl;
713  break;
714  default:
715  stream << "Unknown Type" << endl;
716  break;
717  }
718  }
719 
720  return stream;
721  }
722 
723 
724 
725  MESSAGE_CONSTRUCTORS(DataProcessorStatus, (1 + getProcessCount() * 2))
726 
728 
729  uint8_t DataProcessorStatus::getProcessCount()
730  {
731  return *getPayloadPointer();
732  }
733 
735  {
736  return btoi(getPayloadPointer(1 + process * 2), 2);
737  }
738 
739  ostream &DataProcessorStatus::printMessage(ostream &stream)
740  {
741  stream << "Processor Status" << endl;
742  stream << "================" << endl;
743  stream << "Process Count : " << (int) (getProcessCount()) << endl;
744  for (unsigned int i = 0; i < getProcessCount(); ++i)
745  {
746  stream << "Process " << i << " Errors: " << getErrorCount(i) << endl;
747  }
748  return stream;
749  }
750 
751 
752 
753  MESSAGE_CONSTRUCTORS(DataRangefinders, (1 + getRangefinderCount() * 2))
754 
756 
757  uint8_t DataRangefinders::getRangefinderCount()
758  {
759  return *getPayloadPointer();
760  }
761 
762  double DataRangefinders::getDistance(int rangefinder)
763  {
764  return btof(getPayloadPointer(1 + 2 * rangefinder), 2,1000);
765  }
766 
767  ostream &DataRangefinders::printMessage(ostream &stream)
768  {
769  stream << "Rangefinder Data" << endl;
770  stream << "================" << endl;
771  stream << "Rangefinder Count: " << (int) (getRangefinderCount()) << endl;
772  for (unsigned int i = 0; i < getRangefinderCount(); ++i)
773  {
774  stream << "Distance " << i << " : " << getDistance(i) << endl;
775  }
776  return stream;
777  }
778 
779 
780 
781  MESSAGE_CONSTRUCTORS(DataRangefinderTimings, (1 + getRangefinderCount() * 6))
782 
784 
785  uint8_t DataRangefinderTimings::getRangefinderCount()
786  {
787  return *getPayloadPointer();
788  }
789 
790  double DataRangefinderTimings::getDistance(int rangefinder)
791  {
792  return btof(getPayloadPointer(1 + 2 * rangefinder), 2,1000);
793  }
794 
796  {
797  return btou(getPayloadPointer(1 + 2 * getRangefinderCount() + 4 * rangefinder), 4);
798  }
799 
800  ostream &DataRangefinderTimings::printMessage(ostream &stream)
801  {
802  stream << "Rangefinder Timing Data" << endl;
803  stream << "=======================" << endl;
804  stream << "Rangefinder Count : " << (int) (getRangefinderCount()) << endl;
805  for (unsigned int i = 0; i < getRangefinderCount(); ++i)
806  {
807  stream << "Rangefinder " << i << ":" << endl;
808  stream << " Distance : " << getDistance(i) << endl;
809  stream << " Acquisition Time: " << getAcquisitionTime(i) << endl;
810  }
811  return stream;
812  }
813 
814 
815 
817 
819 
820  uint16_t DataRawAcceleration::getX()
821  {
822  return btou(getPayloadPointer(X), 2);
823  }
824 
826  {
827  return btou(getPayloadPointer(Y), 2);
828  }
829 
831  {
832  return btou(getPayloadPointer(Z), 2);
833  }
834 
835  ostream &DataRawAcceleration::printMessage(ostream &stream)
836  {
837  stream << "Raw Acceleration Data" << endl;
838  stream << "=====================" << endl;
839  stream << "X: 0x" << hex << getX() << endl;
840  stream << "Y: 0x" << getY() << endl;
841  stream << "Z: 0x" << getZ() << dec << endl;
842  return stream;
843  }
844 
845 
846 
847  MESSAGE_CONSTRUCTORS(Data6AxisYaw, PAYLOAD_LEN)
848 
850 
851  double Data6AxisYaw::getAngle()
852  {
853  return btof(getPayloadPointer(Angle), 2, 1000);
854  }
855 
857  {
858  return btof(getPayloadPointer(Angle_rate), 2, 1000);
859  }
860 
861  ostream &Data6AxisYaw::printMessage(ostream &stream)
862  {
863  stream << "Raw Yaw Data" << endl;
864  stream << "=====================" << endl;
865  stream << "Angle: 0x" << hex << getAngle() << endl;
866  stream << "Angle Rate: 0x" << getAngleRate() << endl;
867  return stream;
868  }
869 
870 
871 
872 
873  MESSAGE_CONSTRUCTORS(DataRawCurrent, (1 + getCurrentCount() * 2))
874 
876 
877  uint8_t DataRawCurrent::getCurrentCount()
878  {
879  return *getPayloadPointer();
880  }
881 
882  uint16_t DataRawCurrent::getCurrent(int current)
883  {
884  return btou(getPayloadPointer(1 + current * 2), 2);
885  }
886 
887  ostream &DataRawCurrent::printMessage(ostream &stream)
888  {
889  stream << "Raw Current Data" << endl;
890  stream << "================" << endl;
891  stream << hex;
892  for (unsigned int i = 0; i < getCurrentCount(); ++i)
893  {
894  stream << "Current " << i << ": 0x" << getCurrent(i) << endl;
895  }
896  stream << dec;
897  return stream;
898  }
899 
900 
901 
902  MESSAGE_CONSTRUCTORS(DataRawGyro, PAYLOAD_LEN)
903 
905 
906  uint16_t DataRawGyro::getRoll()
907  {
908  return btou(getPayloadPointer(ROLL), 2);
909  }
910 
912  {
913  return btou(getPayloadPointer(PITCH), 2);
914  }
915 
917  {
918  return btou(getPayloadPointer(YAW), 2);
919  }
920 
921  ostream &DataRawGyro::printMessage(ostream &stream)
922  {
923  stream << "Raw Gyro Data" << endl;
924  stream << "=============" << endl;
925  stream << "Roll : 0x" << hex << getRoll() << endl;
926  stream << "Pitch: 0x" << getPitch() << endl;
927  stream << "Yaw : 0x" << getYaw() << dec << endl;
928  return stream;
929  }
930 
931 
932 
934 
936 
937  uint16_t DataRawMagnetometer::getX()
938  {
939  return btou(getPayloadPointer(X), 2);
940  }
941 
943  {
944  return btou(getPayloadPointer(Y), 2);
945  }
946 
948  {
949  return btou(getPayloadPointer(Z), 2);
950  }
951 
952  ostream &DataRawMagnetometer::printMessage(ostream &stream)
953  {
954  stream << "Raw Magnetometer Data" << endl;
955  stream << "=====================" << endl;
956  stream << "X: 0x" << hex << getX() << endl;
957  stream << "Y: 0x" << getY() << endl;
958  stream << "Z: 0x" << getZ() << dec << endl;
959  return stream;
960  }
961 
962 
963 
965 
967 
968  uint16_t DataRawOrientation::getRoll()
969  {
970  return btou(getPayloadPointer(ROLL), 2);
971  }
972 
974  {
975  return btou(getPayloadPointer(PITCH), 2);
976  }
977 
979  {
980  return btou(getPayloadPointer(YAW), 2);
981  }
982 
983  ostream &DataRawOrientation::printMessage(ostream &stream)
984  {
985  stream << "Raw Orientation Data" << endl;
986  stream << "====================" << endl;
987  stream << "Roll : 0x" << hex << getRoll() << endl;
988  stream << "Pitch: 0x" << getPitch() << endl;
989  stream << "Yaw : 0x" << getYaw() << dec << endl;
990  return stream;
991  }
992 
993 
994 
995  MESSAGE_CONSTRUCTORS(DataRawTemperature, (1 + 2 * getTemperatureCount()))
996 
998 
999  uint8_t DataRawTemperature::getTemperatureCount()
1000  {
1001  return *getPayloadPointer();
1002  }
1003 
1004  uint16_t DataRawTemperature::getTemperature(int temperature)
1005  {
1006  return btou(getPayloadPointer(1 + 2 * temperature), 2);
1007  }
1008 
1009  ostream &DataRawTemperature::printMessage(ostream &stream)
1010  {
1011  stream << "Raw Temperature Data" << endl;
1012  stream << "====================" << endl;
1013  stream << "Temperature Count: " << (int) (getTemperatureCount()) << endl;
1014  stream << hex;
1015  for (unsigned i = 0; i < getTemperatureCount(); ++i)
1016  {
1017  stream << "Temperature " << i << " : 0x" << getTemperature(i) << endl;
1018  }
1019  stream << dec;
1020  return stream;
1021  }
1022 
1023 
1024 
1025  MESSAGE_CONSTRUCTORS(DataRawVoltage, (1 + 2 * getVoltageCount()))
1026 
1028 
1029  uint8_t DataRawVoltage::getVoltageCount()
1030  {
1031  return *getPayloadPointer();
1032  }
1033 
1034  uint16_t DataRawVoltage::getVoltage(int temperature)
1035  {
1036  return btou(getPayloadPointer(1 + 2 * temperature), 2);
1037  }
1038 
1039  ostream &DataRawVoltage::printMessage(ostream &stream)
1040  {
1041  stream << "Raw Voltage Data" << endl;
1042  stream << "================" << endl;
1043  stream << "Voltage Count: " << (int) (getVoltageCount()) << endl;
1044  stream << hex;
1045  for (unsigned i = 0; i < getVoltageCount(); ++i)
1046  {
1047  stream << "Voltage " << i << " : 0x" << getVoltage(i) << endl;
1048  }
1049  stream << dec;
1050  return stream;
1051  }
1052 
1053 
1054 
1056 
1058 
1060  {
1061  return btou(getPayloadPointer(), 2);
1062  }
1063 
1064  ostream &DataSafetySystemStatus::printMessage(ostream &stream)
1065  {
1066  stream << "Safety System Status Data" << endl;
1067  stream << "=========================" << endl;
1068  stream << "Flags: " << getFlags() << endl;
1069  return stream;
1070  }
1071 
1072 
1073  DataSystemStatus::DataSystemStatus(void *input, size_t msg_len) : Message(input, msg_len)
1074  {
1075  voltages_offset = 4;
1078 
1079  size_t expect_len = (7 + 2 * getVoltagesCount() + 2 * getCurrentsCount() + 2 * getTemperaturesCount());
1080  if (getPayloadLength() != expect_len)
1081  {
1082  stringstream ss;
1083  ss << "Bad payload length: actual=" << getPayloadLength();
1084  ss << " vs. expected=" << expect_len;
1085  throw new MessageException(ss.str().c_str(), MessageException::INVALID_LENGTH);
1086  }
1087  }
1088 
1090  {
1091  }
1092 
1094 
1096  {
1097  return btou(getPayloadPointer(0), 4);
1098  }
1099 
1101  {
1103  }
1104 
1105  double DataSystemStatus::getVoltage(uint8_t index)
1106  {
1107  return btof(getPayloadPointer(voltages_offset + 1 + (index * 2)), 2, 100);
1108  }
1109 
1111  {
1113  }
1114 
1115  double DataSystemStatus::getCurrent(uint8_t index)
1116  {
1117  return btof(getPayloadPointer(currents_offset + 1 + (index * 2)), 2, 100);
1118  }
1119 
1121  {
1123  }
1124 
1125  double DataSystemStatus::getTemperature(uint8_t index)
1126  {
1127  return btof(getPayloadPointer(temperatures_offset + 1 + (index * 2)), 2, 100);
1128  }
1129 
1130  ostream &DataSystemStatus::printMessage(ostream &stream)
1131  {
1132  stream << "System Status" << endl;
1133  stream << "=============" << endl;
1134  stream << "Uptime : " << getUptime() << endl;
1135  stream << "Voltage Count : " << (int) (getVoltagesCount()) << endl;
1136  stream << "Voltages : ";
1137  for (unsigned i = 0; i < getVoltagesCount(); ++i)
1138  {
1139  stream << getVoltage(i);
1140  if ((int) i != (getVoltagesCount() - 1)) { stream << ", "; }
1141  }
1142  stream << endl;
1143  stream << "Current Count : " << (int) (getCurrentsCount()) << endl;
1144  stream << "Currents : ";
1145  for (unsigned i = 0; i < getCurrentsCount(); ++i)
1146  {
1147  stream << getCurrent(i);
1148  if ((int) i != (getCurrentsCount() - 1)) { stream << ", "; }
1149  }
1150  stream << endl;
1151  stream << "Temperature Count: " << (int) (getTemperaturesCount()) << endl;
1152  stream << "Temperatures : ";
1153  for (unsigned i = 0; i < getTemperaturesCount(); ++i)
1154  {
1155  stream << getTemperature(i);
1156  if ((int) i != (getTemperaturesCount() - 1)) { stream << ", "; }
1157  }
1158  stream << endl;
1159  return stream;
1160  }
1161 
1162 
1163 
1164  MESSAGE_CONSTRUCTORS(DataVelocity, PAYLOAD_LEN)
1165 
1167 
1168  double DataVelocity::getTranslational()
1169  {
1170  return btof(getPayloadPointer(TRANS_VEL), 2, 100);
1171  }
1172 
1174  {
1175  return btof(getPayloadPointer(ROTATIONAL), 2, 100);
1176  }
1177 
1179  {
1180  return btof(getPayloadPointer(TRANS_ACCEL), 2, 100);
1181  }
1182 
1183  ostream &DataVelocity::printMessage(ostream &stream)
1184  {
1185  stream << "Velocity Setpoints" << endl;
1186  stream << "==================" << endl;
1187  stream << "Translational:" << getTranslational() << endl;
1188  stream << "Rotational: " << getRotational() << endl;
1189  stream << "Trans Accel: " << getTransAccel() << endl;
1190  return stream;
1191  }
1192 
1193 }; // namespace sawyer
1194 
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
DataEncoders(void *input, size_t msg_len)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getDistance(int rangefinder)
uint64_t btou(void *src, size_t src_len)
Definition: Number.cpp:120
TFSIMD_FORCE_INLINE const tfScalar & getX() const
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
::std::string string
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getSpeed(uint8_t index)
MESSAGE_CONVENIENCE_FNS(DataDifferentialSpeed, DATA_DIFF_WHEEL_SPEEDS)
std::string getName(void *handle)
int16_t getErrorCount(int process)
uint8_t * getPayloadPointer(size_t offset=0)
Definition: Message.cpp:218
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getTemperature(uint8_t index)
#define MESSAGE_CONVENIENCE_FNS(MessageClass, DataMsgID)
int32_t getTicks(uint8_t inx)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
geometry_msgs::TransformStamped t
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
size_t getPayloadLength()
Definition: Message.h:161
double getCurrent(uint8_t index)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
uint16_t getTemperature(int temperature)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
#define MESSAGE_CONSTRUCTORS(MessageClass, ExpectedLength)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
int16_t getCapacityEstimate(uint8_t battery)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
uint32_t getAcquisitionTime(int rangefinder)
int64_t btoi(void *src, size_t src_len)
Definition: Number.cpp:135
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getTravel(uint8_t index)
double getVoltage(uint8_t index)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getDistance(int rangefinder)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
BatteryDescription getDescription(uint8_t battery)
uint16_t getVoltage(int temperature)
uint16_t getCurrent(int current)
MESSAGE_CONSTRUCTORS(DataDifferentialSpeed, PAYLOAD_LEN)
double getChargeEstimate(uint8_t battery)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getYaw(const tf2::Quaternion quat)
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double btof(void *src, size_t src_len, double scale)
Definition: Number.cpp:160
DataSystemStatus(void *input, size_t msg_len)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
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:13