Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef FLATHEADERS
00033 #include "simple_message/log_wrapper.h"
00034 #include "simple_message/smpl_msg_connection.h"
00035 #include "simple_message/byte_array.h"
00036 #else
00037 #include "log_wrapper.h"
00038 #include "smpl_msg_connection.h"
00039 #include "byte_array.h"
00040 #endif
00041
00042 #ifdef MOTOPLUS
00043 #include "motoPlus.h"
00044 #endif
00045
00046 using namespace industrial::simple_message;
00047 using namespace industrial::byte_array;
00048
00049 namespace industrial
00050 {
00051
00052 namespace smpl_msg_connection
00053 {
00054
00055
00056 bool SmplMsgConnection::sendMsg(SimpleMessage & message)
00057 {
00058 bool rtn;
00059 ByteArray sendBuffer;
00060 ByteArray msgData;
00061
00062 if (message.validateMessage())
00063 {
00064 message.toByteArray(msgData);
00065 sendBuffer.load((int)msgData.getBufferSize());
00066 sendBuffer.load(msgData);
00067 rtn = this->sendBytes(sendBuffer);
00068 }
00069 else
00070 {
00071 rtn = false;
00072 LOG_ERROR("Message validation failed, message not sent");
00073 }
00074
00075 return rtn;
00076 }
00077
00078
00079 bool SmplMsgConnection::receiveMsg(SimpleMessage & message)
00080 {
00081 ByteArray lengthBuffer;
00082 ByteArray msgBuffer;
00083 int length;
00084
00085 bool rtn = false;
00086
00087
00088 rtn = this->receiveBytes(lengthBuffer, message.getLengthSize());
00089
00090 if (rtn)
00091 {
00092 rtn = lengthBuffer.unload(length);
00093 LOG_COMM("Message length: %d", length);
00094
00095 if (rtn)
00096 {
00097 rtn = this->receiveBytes(msgBuffer, length);
00098
00099 if (rtn)
00100 {
00101 rtn = message.init(msgBuffer);
00102 }
00103 else
00104 {
00105 LOG_ERROR("Failed to initialize message");
00106 rtn = false;
00107 }
00108
00109 }
00110 else
00111 {
00112 LOG_ERROR("Failed to receive message");
00113 rtn = false;
00114 }
00115 }
00116 else
00117 {
00118 LOG_ERROR("Failed to receive message length");
00119 rtn = false;
00120 }
00121
00122 return rtn;
00123 }
00124
00125
00126
00127 bool SmplMsgConnection::sendAndReceiveMsg(SimpleMessage & send, SimpleMessage & recv, bool verbose)
00128 {
00129 bool rtn = false;
00130 rtn = this->sendMsg(send);
00131 if (rtn)
00132 {
00133 if(verbose) {
00134 LOG_ERROR("Sent message");
00135 }
00136 rtn = this->receiveMsg(recv);
00137 if(verbose) {
00138 LOG_ERROR("Got message");
00139 }
00140 }
00141 else
00142 {
00143 rtn = false;
00144 }
00145
00146 return rtn;
00147 }
00148
00149
00150 }
00151 }