Message.cpp
Go to the documentation of this file.
00001 
00047 #include <unistd.h>
00048 #include <iostream>
00049 #include <string.h>
00050 #include "roch_base/core/crc.h"
00051 #include "roch_base/core/Message.h"
00052 #include "roch_base/core/Message_data.h"
00053 #include "roch_base/core/Number.h"
00054 #include "roch_base/core/Transport.h"
00055 #include <stdio.h>
00056 #ifdef DEBUG_INFO
00057 #include "roch_base/roch_hardware.h"
00058 #endif
00059 // Conditions on the below to handle compiling for nonstandard hardware
00060 #ifdef LOGGING_AVAIL
00061 #include "roch_base/core/Logger.h"
00062 #endif
00063 
00064 using namespace std;
00065 
00066 namespace sawyer
00067 {
00068 
00069   MessageException::MessageException(const char *msg, enum errors ex_type)
00070       : Exception(msg), type(ex_type)
00071   {
00072 #ifdef LOGGING_AVAIL
00073         CPR_EXCEPT() << "MessageException "<<type<<": "<< message << endl << flush;
00074 #endif
00075   }
00076 
00077   Message::Message() :
00078       is_sent(false)
00079   {
00080     total_len = HEADER_LENGTH + CRC_LENGTH;
00081     memset(data, 0, MAX_MSG_LENGTH);
00082   }
00083 
00084   Message::Message(void *input, size_t msg_len) :
00085       is_sent(false)
00086   {
00087     total_len = msg_len;
00088     memset(data, 0, MAX_MSG_LENGTH);
00089     memcpy(data, input, msg_len);
00090     
00091   }
00092 
00093   Message::Message(const Message &other) :
00094       is_sent(false)
00095   {
00096     total_len = other.total_len;
00097     memset(data, 0, MAX_MSG_LENGTH);
00098     memcpy(data, other.data, total_len);
00099   }
00100 
00101 Message::Message(uint16_t type, uint8_t *payload, size_t payload_len,
00102     uint32_t timestamp, uint8_t flags, uint8_t version) :
00103       is_sent(false)
00104   {
00105     /* Copy in data */
00106     total_len = HEADER_LENGTH + payload_len + CRC_LENGTH;
00107     if (total_len > MAX_MSG_LENGTH)
00108     {
00109       /* If payload is too long, the only recourse we have in constructor
00110        * (other than an abort()) is to truncate silently. */
00111       total_len = MAX_MSG_LENGTH;
00112       payload_len = (MAX_MSG_LENGTH - HEADER_LENGTH - CRC_LENGTH);
00113     }
00114     memset(data, 0, MAX_MSG_LENGTH);
00115     memcpy(data + PAYLOAD_OFST, payload, payload_len);
00116 
00117     /* Fill header */
00118     data[SOH_OFST] = SOH;
00119     setLength(total_len - 3);
00120     setType(type);
00121     setFlags(flags);
00122     setVersion(version);
00123     data[STX_OFST] = STX;
00124 
00125     /* Generate checksum */
00126     uint16_t checksum = crc16(crcOffset(), CRC_INIT_VAL, data);
00127     utob(data + crcOffset(), 2, checksum);
00128     
00129   }
00130 
00131   Message::~Message()
00132   {
00133     // nothing to do, actually.
00134   }
00135 
00136   void Message::send()
00137   {
00138     
00139     // We will retry up to 3 times if we receive CRC errors
00140     for (int i = 0; i < 2; ++i)
00141     {
00142       try
00143       {
00144         
00145         Transport::instance().send(this);
00146         return;
00147       }
00148       catch (BadAckException *ex)
00149       {
00150         // Any bad ack other than bad checksum needs to
00151         // be thrown on
00152         if (ex->ack_flag != BadAckException::BAD_CHECKSUM)
00153         {
00154           throw ex;
00155         }
00156       }
00157     }
00158 
00159     /* Make the final attempt outside the try, so any exception
00160      * just goes straight through */
00161 #ifdef LOGGING_AVAIL
00162     CPR_WARN() << "Bad checksum twice in a row." << endl;
00163 #endif
00164     Transport::instance().send(this);
00165   }
00166 
00167 
00168   Message* Message::sendRequest()
00169   {
00170     Message * getMessage=NULL;
00171     // We will retry up to 3 times if we receive CRC errors
00172     for (int i = 0; i < 2; ++i)
00173     {
00174       try
00175       {
00176         
00177         getMessage = Transport::instance().sendRequest(this);
00178         return getMessage;
00179       }
00180       catch (BadAckException *ex)
00181       {
00182         // Any bad ack other than bad checksum needs to
00183         // be thrown on
00184         if (ex->ack_flag != BadAckException::BAD_CHECKSUM)
00185         {
00186           throw ex;
00187         }
00188       }
00189     }
00190 
00191     /* Make the final attempt outside the try, so any exception
00192      * just goes straight through */
00193 #ifdef LOGGING_AVAIL
00194     CPR_WARN() << "Bad checksum twice in a row." << endl;
00195 #endif
00196     Transport::instance().sendRequest(this);
00197   }
00204   size_t Message::getPayload(void *buf, size_t buf_size)
00205   {
00206     // If we don't have enough space in the buffer, don't even try
00207     if (getPayloadLength() > buf_size) { return 0; }
00208 
00209     memcpy(buf, data + PAYLOAD_OFST, getPayloadLength());
00210     return getPayloadLength();
00211   }
00212 
00218   uint8_t *Message::getPayloadPointer(size_t offset)
00219   {
00220     return data + PAYLOAD_OFST + offset;
00221   }
00222 
00223   uint8_t  Message::getLength()
00224   {
00225     return data[LENGTH_OFST];
00226   }
00227 
00228   uint8_t  Message::getLengthComp()
00229   {
00230     return data[LENGTH_COMP_OFST];
00231   }
00232 
00233   uint8_t  Message::getVersion()
00234   {
00235     return data[VERSION_OFST];
00236   }
00237 
00238   uint8_t  Message::getFlags()
00239   {
00240     return data[FLAGS_OFST];
00241   }
00242 
00243   uint16_t Message::getType() 
00244   {
00245     return btou(data + TYPE_OFST, 2);
00246   }
00247 
00248   uint16_t Message::getChecksum()
00249   {
00250     return btou(data + crcOffset(), 2);
00251   }
00252 
00253   void Message::setLength(uint8_t len)
00254   {
00255     size_t new_total_len = len + 3;
00256     if (new_total_len > MAX_MSG_LENGTH) { return; }
00257     total_len = new_total_len;
00258     data[LENGTH_OFST] = len;
00259     data[LENGTH_COMP_OFST] = ~len;
00260   }
00261 
00262   void Message::setVersion(uint8_t version)
00263   {
00264     data[VERSION_OFST] = version;
00265   }
00266 
00267   void Message::setFlags(uint8_t flags)
00268   {
00269     data[FLAGS_OFST] = flags;
00270   }
00271 
00272   void Message::setType(uint16_t type)
00273   {
00274     utob(data + TYPE_OFST, 2, type);
00275   }
00282   void Message::setPayloadLength(uint8_t len)
00283   {
00284 
00285     if (((size_t) (len) + HEADER_LENGTH + CRC_LENGTH) > MAX_MSG_LENGTH) { return; }
00286     total_len = len + HEADER_LENGTH + CRC_LENGTH; 
00287   }
00288 
00296   void Message::setPayload(void *buf, size_t buf_size)
00297   {
00298     if ((buf_size + HEADER_LENGTH + CRC_LENGTH) > MAX_MSG_LENGTH) { return; }//�±� *2
00299     setPayloadLength(buf_size);
00300     if (buf_size > getPayloadLength()) { return; }
00301     memcpy(data + PAYLOAD_OFST, buf, buf_size);
00302   }
00303 
00304 
00311   size_t Message::toBytes(void *buf, size_t buf_size)
00312   {
00313     // If we don't have enough space in the buffer, don't even try
00314     if (total_len > buf_size)
00315     {
00316       return 0;
00317     }
00318     memcpy(buf, data, total_len);
00319     return total_len;
00320   }
00321 
00329   bool Message::isValid(char *whyNot, size_t strLen)
00330   {
00331     // Check SOH 
00332     if (data[SOH_OFST] != SOH)
00333     {
00334       if (whyNot) { strncpy(whyNot, "SOH is not present.", strLen); }
00335       return false;
00336     }
00337     // Check STX
00338     if (data[STX_OFST] != STX)
00339     {
00340       if (whyNot) { strncpy(whyNot, "STX is not present.", strLen); }
00341       return false;
00342     }
00343     // Check length matches complement
00344     if (getLength() != ((~getLengthComp()) & 0xff))
00345     {
00346       if (whyNot) { strncpy(whyNot, "Length does not match complement.", strLen); }
00347       return false;
00348     }
00349     // Check length is correct
00350     if (getLength() != (total_len - 3))
00351     {
00352       if (whyNot) { strncpy(whyNot, "Length is wrong.", strLen); }
00353       return false;
00354     }
00355     // Check the CRC
00356     if (crc16(crcOffset(), CRC_INIT_VAL, this->data) != getChecksum())
00357     {
00358       if (whyNot) { strncpy(whyNot, "CRC is wrong.", strLen); }
00359 #ifdef DEBUG_INFO
00360           for (int i=0; i<crcOffset(); ++i) printf(" %x", (unsigned char)(this->data[i]));
00361           printf(" crc16:%x  getChecksum:%x",(unsigned char)(crc16(crcOffset(), CRC_INIT_VAL, this->data)),getChecksum());
00362           printf("\r\n");
00363 #endif
00364       return false;
00365     }
00366     return true;
00367   }
00368 
00372   void Message::makeValid()
00373   {
00374     data[SOH_OFST] = SOH;
00375     data[STX_OFST] = STX;
00376     data[LENGTH_OFST] = total_len - 3;
00377     data[LENGTH_COMP_OFST] = ~data[LENGTH_OFST];
00378     uint16_t checksum = crc16(crcOffset(), CRC_INIT_VAL, data);
00379     utob(data + crcOffset(), 2, checksum);
00380 #ifdef DEBUG_INFO
00381     std::cout<<"message data:";
00382     for(int i = 0 ; i < total_len;i++){
00383       printf(" %x",(unsigned char)(data[i]));
00384     }
00385     std::cout<<" !!"<<std::endl;
00386 #endif
00387   }
00388 
00389   std::ostream &Message::printMessage(std::ostream &stream)
00390   {
00391     stream << "Message" << endl;
00392     stream << "=======" << endl;
00393     stream << "Length   : " << (int) (getLength()) << endl;
00394     stream << "~Length  : " << (int) (getLengthComp()) << endl;
00395     stream << "Version  : " << (int) (getVersion()) << endl;
00396     stream << "Flags    : " << hex << (int) (getFlags()) << endl;
00397     stream << "Type     : " << hex << (int) (getType()) << endl;//ԭ�� �±�����Ϊ�ɱ�
00398     stream << "Checksum : " << hex << (int) (getChecksum()) << endl;
00399     stream << dec;
00400     stream << "Raw      : ";
00401     printRaw(stream);
00402     return stream;
00403   }
00404 
00405   void Message::printRaw(std::ostream &stream)
00406   {
00407     stream << hex << uppercase;
00408     for (unsigned int i = 0; i < total_len; i++)
00409     {
00410       stream << static_cast<short>(data[i]) << " ";
00411     }
00412     stream << dec;
00413     stream << endl;
00414   }
00415 
00423   Message *Message::factory(void *input, size_t msg_len)
00424   {
00425     uint16_t type = btou((char *) input + TYPE_OFST, 2);
00426     switch (type)
00427     {
00428       case DATA_ACCEL:
00429         return new DataPlatformAcceleration(input, msg_len);
00430 
00431       case DATA_ACCEL_RAW:
00432         return new DataRawAcceleration(input, msg_len);
00433 
00434       case DATA_6AXIS_YAW:
00435         return new Data6AxisYaw(input, msg_len);
00436 
00437       case DATA_ACKERMANN_SETPTS:
00438         return new DataAckermannOutput(input, msg_len);
00439 
00440       case DATA_CURRENT_RAW:
00441         return new DataRawCurrent(input, msg_len);
00442 
00443       case DATA_PLATFORM_NAME:
00444         return new DataPlatformName(input, msg_len);
00445 
00446       case DATA_DIFF_CTRL_CONSTS:
00447         return new DataDifferentialControl(input, msg_len);
00448 
00449       case DATA_DIFF_WHEEL_SPEEDS:
00450         return new DataDifferentialSpeed(input, msg_len);
00451 
00452       case DATA_DIFF_WHEEL_SETPTS:
00453         return new DataDifferentialOutput(input, msg_len);
00454 
00455       case DATA_WHEEL_INFO:
00456         return new DataWheelInfo(input,msg_len);
00457 
00458       case DATA_DISTANCE_DATA:
00459         return new DataRangefinders(input, msg_len);
00460 
00461       case DATA_DISTANCE_TIMING:
00462         return new DataRangefinderTimings(input, msg_len);
00463 
00464       case DATA_ECHO:
00465         return new DataEcho(input, msg_len);
00466 
00467       case DATA_ENCODER:
00468         return new DataEncoders(input, msg_len);
00469 
00470       case DATA_ENCODER_RAW:
00471         return new DataEncodersRaw(input, msg_len);
00472 
00473       case DATA_FIRMWARE_INFO:
00474         return new DataFirmwareInfo(input, msg_len);
00475 
00476       case DATA_GYRO_RAW:
00477         return new DataRawGyro(input, msg_len);
00478 
00479       case DATA_MAGNETOMETER:
00480         return new DataPlatformMagnetometer(input, msg_len);
00481 
00482       case DATA_MAGNETOMETER_RAW:
00483         return new DataRawMagnetometer(input, msg_len);
00484 
00485       case DATA_XYZ_DATA:
00486         return new DataXYZData(input, msg_len);
00487 
00488       case DATA_MAX_ACCEL:
00489         return new DataMaxAcceleration(input, msg_len);
00490 
00491       case DATA_MAX_SPEED:
00492         return new DataMaxSpeed(input, msg_len);
00493 
00494       case DATA_ORIENT:
00495         return new DataPlatformOrientation(input, msg_len);
00496 
00497       case DATA_ORIENT_RAW:
00498         return new DataRawOrientation(input, msg_len);
00499 
00500       case DATA_PLATFORM_INFO:
00501         return new DataPlatformInfo(input, msg_len);
00502 
00503       case DATA_POWER_SYSTEM:
00504         return new DataPowerSystem(input, msg_len);
00505 
00506       case DATA_PROC_STATUS:
00507         return new DataProcessorStatus(input, msg_len);
00508 
00509       case DATA_ROT_RATE:
00510         return new DataPlatformRotation(input, msg_len);
00511 
00512       case DATA_SAFETY_SYSTEM:
00513         return new DataSafetySystemStatus(input, msg_len);
00514 
00515       case DATA_SYSTEM_STATUS:
00516         return new DataSystemStatus(input, msg_len);
00517 
00518       case DATA_TEMPERATURE_RAW:
00519         return new DataRawTemperature(input, msg_len);
00520 
00521       case DATA_VELOCITY_SETPT:
00522         return new DataVelocity(input, msg_len);
00523 
00524       case DATA_VOLTAGE_RAW:
00525         return new DataRawVoltage(input, msg_len);
00526 
00527       default:
00528         return new Message(input, msg_len);
00529     } // switch getType()
00530   } // factory()
00531 
00532   Message *Message::popNext()
00533   {
00534     return Transport::instance().popNext();
00535   }
00536 
00537   Message *Message::waitNext(double timeout)
00538   {
00539     return Transport::instance().waitNext(timeout);
00540   }
00541 
00542 }; // namespace sawyer
00543 
00544 std::ostream &operator<<(std::ostream &stream, sawyer::Message &msg)
00545 {
00546   return msg.printMessage(stream);
00547 }
00548 


roch_base
Author(s): Mike Purvis , Paul Bovbel , Carl
autogenerated on Sat Jun 8 2019 20:32:33