24 #define MESSAGE_CONSTRUCTORS(MessageClass, ExpectedLength) \ 25 MessageClass::MessageClass(void* input, size_t msg_len) : Message(input, msg_len) \ 27 if( ((ExpectedLength) >= 0) && ((ssize_t)getPayloadLength() != (ExpectedLength)) ) { \ 29 ss << "Bad payload length: actual="<<getPayloadLength(); \ 30 ss <<" vs. expected="<<(ExpectedLength); \ 31 throw new MessageException(ss.str().c_str(), MessageException::INVALID_LENGTH); \ 34 MessageClass::MessageClass(const MessageClass& other) : Message(other) {} 41 #define MESSAGE_CONVENIENCE_FNS(MessageClass, DataMsgID) \ 42 MessageClass* MessageClass::popNext() { \ 43 return dynamic_cast<MessageClass*>( Transport::instance().popNext(DataMsgID)); \ 46 MessageClass* MessageClass::waitNext(double timeout) { \ 47 return dynamic_cast<MessageClass*>(Transport::instance().waitNext(DataMsgID, timeout)); \ 50 MessageClass* MessageClass::getUpdate(double timeout) { \ 52 return dynamic_cast<MessageClass*>( \ 53 Transport::instance().waitNext(DataMsgID, timeout) ); \ 56 void MessageClass::subscribe(uint16_t freq) { \ 57 Request(DataMsgID-0x4000, freq).sendRequest(); \ 60 enum MessageTypes MessageClass::getTypeID() { \ 67 double DataAckermannOutput::getSteering()
69 return btof(getPayloadPointer(STEERING), 2, 100);
72 double DataAckermannOutput::getThrottle()
74 return btof(getPayloadPointer(THROTTLE), 2, 100);
77 double DataAckermannOutput::getBrake()
79 return btof(getPayloadPointer(BRAKE), 2, 100);
82 ostream &DataAckermannOutput::printMessage(ostream &stream)
84 stream <<
"Ackermann Control" << endl;
85 stream <<
"=================" << endl;
86 stream <<
"Steering: " << getSteering() << endl;
87 stream <<
"Throttle: " << getThrottle() << endl;
88 stream <<
"Brake : " << getBrake() << endl;
100 return btof(getPayloadPointer(LEFT_P), 2, 10000);
103 double DataDifferentialControl::getLeftI()
105 return btof(getPayloadPointer(LEFT_I), 2, 10000);
108 double DataDifferentialControl::getLeftD()
110 return btof(getPayloadPointer(LEFT_D), 2, 10000);
113 double DataDifferentialControl::getRightP()
115 return btof(getPayloadPointer(RIGHT_P), 2, 10000);
118 double DataDifferentialControl::getRightI()
120 return btof(getPayloadPointer(RIGHT_I), 2, 10000);
123 double DataDifferentialControl::getRightD()
125 return btof(getPayloadPointer(RIGHT_D), 2, 10000);
128 ostream &DataDifferentialControl::printMessage(ostream &stream)
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;
148 return btof(getPayloadPointer(LEFT), 2, 100);
151 double DataDifferentialOutput::getRight()
153 return btof(getPayloadPointer(RIGHT), 2, 100);
156 ostream &DataDifferentialOutput::printMessage(ostream &stream)
158 stream <<
"Differential Output Data" << endl;
159 stream <<
"========================" << endl;
160 stream <<
"Left : " << getLeft() << endl;
161 stream <<
"Right: " << getRight() << endl;
171 double DataDifferentialSpeed::getLeftSpeed()
173 return btof(getPayloadPointer(LEFT_SPEED), 2, 100);
176 double DataDifferentialSpeed::getLeftAccel()
178 return btof(getPayloadPointer(LEFT_ACCEL), 2, 100);
181 double DataDifferentialSpeed::getRightSpeed()
183 return btof(getPayloadPointer(RIGHT_SPEED), 2, 100);
186 double DataDifferentialSpeed::getRightAccel()
188 return btof(getPayloadPointer(RIGHT_ACCEL), 2, 100);
191 ostream &DataDifferentialSpeed::printMessage(ostream &stream)
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;
207 double DataWheelInfo::getWheelGauge()
209 return btof(getPayloadPointer(WHEEL_GAUGE), 2, 10000);
212 double DataWheelInfo::getWheelDiameter()
214 return btof(getPayloadPointer(WHEEL_DIAMETER), 2, 10000);
217 ostream &DataWheelInfo::printMessage(ostream &stream)
219 stream <<
"Wheel Information" << endl;
220 stream <<
"=======================" << endl;
221 stream <<
"Wheel Gauge : " << getWheelGauge() << endl;
222 stream <<
"Wheel Diameter : " << getWheelDiameter() << endl;
237 DataEncoders::DataEncoders(
void *input,
size_t msg_len) :
Message(input, msg_len)
243 ss <<
" vs. expected=" << (1 +
getCount() * 6);
273 stream <<
"Encoder Data" << endl;
274 stream <<
"============" << endl;
275 stream <<
"Count : " << (int) (
getCount()) << endl;
276 for (
unsigned i = 0; i <
getCount(); ++i)
278 stream <<
"Encoder " << i <<
":" << endl;
279 stream <<
" Travel: " <<
getTravel(i) << endl;
280 stream <<
" Speed : " <<
getSpeed(i) << endl;
303 stream <<
"Raw Encoder Data" << endl;
304 stream <<
"================" << endl;
305 for (
int i = 0; i <
getCount(); ++i)
307 stream <<
"Encoder " << i <<
": " << getTicks(i) << endl;
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;
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;
371 stream <<
"Gear" << endl;
372 stream <<
"====" << endl;
373 stream <<
"Gear: " << (int) getGear() << endl;
395 stream <<
"Max Acceleration Data" << endl;
396 stream <<
"=====================" << endl;
397 stream <<
"Max Forward: " << getForwardMax() << endl;
398 stream <<
"Max Reverse: " << getReverseMax() << endl;
420 stream <<
"Max Speed Data" << endl;
421 stream <<
"==============" << endl;
422 stream <<
"Max Forward: " << getForwardMax() << endl;
423 stream <<
"Max Reverse: " << getReverseMax() << endl;
450 stream <<
"Platform Acceleration" << endl;
451 stream <<
"=====================" << endl;
452 stream <<
"X: " <<
getX() << endl;
453 stream <<
"Y: " <<
getY() << endl;
454 stream <<
"Z: " <<
getZ() << endl;
464 uint8_t DataPlatformInfo::strlenModel()
473 size_t cpy_len = strlenModel();
482 char offset = strlenModel() + 1;
488 char offset = strlenModel() + 2;
494 stream <<
"Platform Info" << endl;
495 stream <<
"=============" << endl;
496 stream <<
"Model : " << getModel() << endl;
497 stream <<
"Revision: " << (int) (getRevision()) << endl;
498 stream <<
"Serial : " << getSerial() << endl;
508 string DataPlatformName::getName()
519 stream <<
"Platform Name" << endl;
520 stream <<
"=============" << endl;
521 stream <<
"Name: " <<
getName() << endl;
548 stream <<
"PlatformMagnetometer Data" << endl;
549 stream <<
"=================" << endl;
550 stream <<
"X: " <<
getX() << endl;
551 stream <<
"Y: " <<
getY() << endl;
552 stream <<
"Z: " <<
getZ() << endl;
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;
609 stream <<
"Platform Orientation" << endl;
610 stream <<
"====================" << endl;
611 stream <<
"Roll : " << getRoll() << endl;
612 stream <<
"Pitch: " << getPitch() << endl;
613 stream <<
"Yaw : " <<
getYaw() << endl;
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;
670 + 2 * getBatteryCount()
678 + 4 * getBatteryCount()
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)
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())
699 case BatteryDescription::EXTERNAL:
700 stream <<
"External" << endl;
702 case BatteryDescription::LEAD_ACID:
703 stream <<
"Lead-Acid" << endl;
705 case BatteryDescription::NIMH:
706 stream <<
"NiMH" << endl;
708 case BatteryDescription::Li_ion:
709 stream <<
"Li_ion" << endl;
711 case BatteryDescription::GASOLINE:
712 stream <<
"Internal Combustion Engine" << endl;
715 stream <<
"Unknown Type" << endl;
729 uint8_t DataProcessorStatus::getProcessCount()
741 stream <<
"Processor Status" << endl;
742 stream <<
"================" << endl;
743 stream <<
"Process Count : " << (int) (getProcessCount()) << endl;
744 for (
unsigned int i = 0; i < getProcessCount(); ++i)
746 stream <<
"Process " << i <<
" Errors: " << getErrorCount(i) << endl;
757 uint8_t DataRangefinders::getRangefinderCount()
769 stream <<
"Rangefinder Data" << endl;
770 stream <<
"================" << endl;
771 stream <<
"Rangefinder Count: " << (int) (getRangefinderCount()) << endl;
772 for (
unsigned int i = 0; i < getRangefinderCount(); ++i)
774 stream <<
"Distance " << i <<
" : " << getDistance(i) << endl;
785 uint8_t DataRangefinderTimings::getRangefinderCount()
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)
807 stream <<
"Rangefinder " << i <<
":" << endl;
808 stream <<
" Distance : " << getDistance(i) << endl;
809 stream <<
" Acquisition Time: " << getAcquisitionTime(i) << endl;
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;
863 stream <<
"Raw Yaw Data" << endl;
864 stream <<
"=====================" << endl;
865 stream <<
"Angle: 0x" << hex << getAngle() << endl;
866 stream <<
"Angle Rate: 0x" << getAngleRate() << endl;
877 uint8_t DataRawCurrent::getCurrentCount()
889 stream <<
"Raw Current Data" << endl;
890 stream <<
"================" << endl;
892 for (
unsigned int i = 0; i < getCurrentCount(); ++i)
894 stream <<
"Current " << i <<
": 0x" << getCurrent(i) << endl;
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;
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;
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;
999 uint8_t DataRawTemperature::getTemperatureCount()
1011 stream <<
"Raw Temperature Data" << endl;
1012 stream <<
"====================" << endl;
1013 stream <<
"Temperature Count: " << (int) (getTemperatureCount()) << endl;
1015 for (
unsigned i = 0; i < getTemperatureCount(); ++i)
1017 stream <<
"Temperature " << i <<
" : 0x" << getTemperature(i) << endl;
1029 uint8_t DataRawVoltage::getVoltageCount()
1041 stream <<
"Raw Voltage Data" << endl;
1042 stream <<
"================" << endl;
1043 stream <<
"Voltage Count: " << (int) (getVoltageCount()) << endl;
1045 for (
unsigned i = 0; i < getVoltageCount(); ++i)
1047 stream <<
"Voltage " << i <<
" : 0x" << getVoltage(i) << endl;
1066 stream <<
"Safety System Status Data" << endl;
1067 stream <<
"=========================" << endl;
1068 stream <<
"Flags: " <<
getFlags() << endl;
1084 ss <<
" vs. expected=" << expect_len;
1132 stream <<
"System Status" << endl;
1133 stream <<
"=============" << endl;
1134 stream <<
"Uptime : " <<
getUptime() << endl;
1136 stream <<
"Voltages : ";
1144 stream <<
"Currents : ";
1152 stream <<
"Temperatures : ";
1185 stream <<
"Velocity Setpoints" << endl;
1186 stream <<
"==================" << endl;
1187 stream <<
"Translational:" << getTranslational() << endl;
1188 stream <<
"Rotational: " << getRotational() << endl;
1189 stream <<
"Trans Accel: " << getTransAccel() << endl;
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)
uint8_t getTemperaturesCount()
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
double getDistance(int rangefinder)
uint64_t btou(void *src, size_t src_len)
TFSIMD_FORCE_INLINE const tfScalar & getX() const
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
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)
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)
geometry_msgs::TransformStamped t
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
size_t getPayloadLength()
double getCurrent(uint8_t index)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
uint16_t getTemperature(int temperature)
uint8_t getMinorProtocolVersion()
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)
uint32_t getAcquisitionTime(int rangefinder)
int64_t btoi(void *src, size_t src_len)
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)
double getDistance(int rangefinder)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
uint8_t getCurrentsCount()
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
BatteryDescription getDescription(uint8_t battery)
uint8_t getMinorFirmwareVersion()
uint8_t getMajorProtocolVersion()
uint16_t getVoltage(int temperature)
uint16_t getCurrent(int current)
MESSAGE_CONSTRUCTORS(DataDifferentialSpeed, PAYLOAD_LEN)
double getChargeEstimate(uint8_t battery)
uint8_t temperatures_offset
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)
DataSystemStatus(void *input, size_t msg_len)
virtual std::ostream & printMessage(std::ostream &stream=std::cout)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
uint8_t getVoltagesCount()