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