session.cpp
Go to the documentation of this file.
00001 
00026 #include <boost/bind.hpp>
00027 #include <boost/shared_ptr.hpp>
00028 #include <boost/make_shared.hpp>
00029 #include <boost/random/mersenne_twister.hpp>
00030 #include <boost/random/uniform_int_distribution.hpp>
00031 
00032 #include "odva_ethernetip/serialization/buffer_reader.h"
00033 #include "odva_ethernetip/serialization/buffer_writer.h"
00034 #include "odva_ethernetip/session.h"
00035 #include "odva_ethernetip/eip_types.h"
00036 #include "odva_ethernetip/encap_packet.h"
00037 #include "odva_ethernetip/register_session_data.h"
00038 #include "odva_ethernetip/rr_data_request.h"
00039 #include "odva_ethernetip/rr_data_response.h"
00040 
00041 using boost::shared_ptr;
00042 using boost::make_shared;
00043 using std::cerr;
00044 using std::cout;
00045 using std::endl;
00046 
00047 namespace eip {
00048 
00049 using serialization::BufferReader;
00050 using serialization::BufferWriter;
00051 
00052 Session::Session(shared_ptr<Socket> socket, shared_ptr<Socket> io_socket,
00053     EIP_UINT vendor_id, EIP_UDINT serial_num)
00054     : socket_(socket), io_socket_(io_socket), session_id_(0),
00055       my_vendor_id_(vendor_id), my_serial_num_(serial_num)
00056 {
00057   // generate pseudo-random connection ID and connection SN starting points
00058   boost::random::mt19937 gen;
00059   gen.seed(std::time(0));
00060   boost::random::uniform_int_distribution<> dist(0, 0xFFFF);
00061   next_connection_id_ = gen();
00062   next_connection_sn_ = dist(gen);
00063   cout << "Generated starting connection ID " << next_connection_id_
00064     << " and SN " << next_connection_sn_ << endl;;
00065 }
00066 
00067 Session::~Session()
00068 {
00069   try
00070   {
00071     if (session_id_ != 0)
00072     {
00073       close();
00074     }
00075   }
00076   catch (...)
00077   {
00078     // can't throw exceptions, but can't do anything either
00079   }
00080 }
00081 
00082 void Session::open(string hostname, string port, string io_port)
00083 {
00084   cout << "Resolving hostname and connecting socket" << endl;
00085   socket_->open(hostname, port);
00086   io_socket_->open(hostname, io_port);
00087 
00088   // create the registration message
00089   cout << "Creating and sending the registration message" << endl;
00090   shared_ptr<RegisterSessionData> reg_data = make_shared<RegisterSessionData>();
00091   EncapPacket reg_msg(EIP_CMD_REGISTER_SESSION, 0, reg_data);
00092 
00093   // send the register session message and get response
00094   EncapPacket response;
00095   try
00096   {
00097     response = sendCommand(reg_msg);
00098   }
00099   catch (std::length_error ex)
00100   {
00101     socket_->close();
00102     io_socket_->close();
00103     cerr << "Could not parse response when registering session: " << ex.what() << endl;
00104     throw std::runtime_error("Invalid response received registering session");
00105   }
00106   catch (std::logic_error ex)
00107   {
00108     socket_->close();
00109     io_socket_->close();
00110     cerr << "Error in registration response: " << ex.what() << endl;
00111     throw std::runtime_error("Error in registration response");
00112   }
00113 
00114   if (response.getHeader().length != reg_data->getLength())
00115   {
00116     cerr << "Warning: Registration message received with wrong size. Expected "
00117        << reg_data->getLength() << " bytes, received "
00118        << response.getHeader().length << endl;
00119   }
00120 
00121   bool response_valid = false;
00122   try
00123   {
00124     response.getPayloadAs(*reg_data);
00125     response_valid = true;
00126   }
00127   catch (std::length_error ex)
00128   {
00129     cerr << "Warning: Registration message too short, ignoring" << endl;
00130   }
00131   catch (std::logic_error ex)
00132   {
00133     cerr << "Warning: could not parse registration response: " << ex.what() << endl;
00134   }
00135 
00136   if (response_valid && reg_data->protocol_version != EIP_PROTOCOL_VERSION)
00137   {
00138     cerr << "Error: Wrong Ethernet Industrial Protocol Version. "
00139       "Expected " << EIP_PROTOCOL_VERSION << " got "
00140       << reg_data->protocol_version << endl;
00141     socket_->close();
00142     io_socket_->close();
00143     throw std::runtime_error("Received wrong Ethernet IP Protocol Version on registration");
00144   }
00145   if (response_valid && reg_data->options != 0)
00146   {
00147     cerr << "Warning: Registration message included non-zero options flags: "
00148       << reg_data->options << endl;
00149   }
00150 
00151   session_id_ = response.getHeader().session_handle;
00152   cout << "Successfully opened session ID " << session_id_ << endl;
00153 }
00154 
00155 void Session::close()
00156 {
00157   // TODO: should close all connections and the IO port
00158   cout << "Closing session" << endl;
00159 
00160   // create the unregister session message
00161   EncapPacket reg_msg(EIP_CMD_UNREGISTER_SESSION, session_id_);
00162   socket_->send(reg_msg);
00163 
00164   cout << "Session closed" << endl;
00165 
00166   socket_->close();
00167   io_socket_->close();
00168   session_id_ = 0;
00169 }
00170 
00171 EncapPacket Session::sendCommand(EncapPacket& req)
00172 {
00173   cout << "Sending Command" << endl;
00174   socket_->send(req);
00175 
00176   cout << "Waiting for response" << endl;
00177   size_t n = socket_->receive(buffer(recv_buffer_));
00178   cout << "Received response of " << n << " bytes" << endl;
00179 
00180   BufferReader reader(buffer(recv_buffer_, n));
00181   EncapPacket result;
00182   result.deserialize(reader);
00183 
00184   if (reader.getByteCount() != n)
00185   {
00186     cerr << "Warning: packet received with " << n <<
00187       " bytes, but only " << reader.getByteCount() << " bytes used" << endl;
00188   }
00189 
00190   check_packet(result, req.getHeader().command);
00191   return result;
00192 }
00193 
00194 void Session::check_packet(EncapPacket& pkt, EIP_UINT exp_cmd)
00195 {
00196   // verify that all fields are correct
00197   if (pkt.getHeader().command != exp_cmd)
00198   {
00199     cerr << "Reply received with wrong command. Expected "
00200       << exp_cmd << ", received " << pkt.getHeader().command << endl;
00201     throw std::logic_error("Reply received with wrong command");
00202   }
00203   if (session_id_ == 0 && pkt.getHeader().session_handle == 0)
00204   {
00205     cerr << "Warning: Zero session handle received on registration: "
00206       << pkt.getHeader().session_handle << endl;
00207     throw std::logic_error("Zero session handle received on registration");
00208   }
00209   if (session_id_ != 0 && pkt.getHeader().session_handle != session_id_)
00210   {
00211     cerr << "Warning: reply received with wrong session ID. Expected "
00212       << session_id_ << ", recieved " << pkt.getHeader().session_handle << endl;
00213     throw std::logic_error("Wrong session ID received for command");
00214   }
00215   if (pkt.getHeader().status != 0)
00216   {
00217     cerr << "Warning: Non-zero status received: " << pkt.getHeader().status << endl;
00218   }
00219   if (pkt.getHeader().context[0] != 0 || pkt.getHeader().context[1] != 0)
00220   {
00221     cerr << "Warning: Non-zero sender context received: "
00222     << pkt.getHeader().context[0] << " / " << pkt.getHeader().context[1] << endl;
00223   }
00224   if (pkt.getHeader().options != 0)
00225   {
00226     cerr << "Warning: Non-zero options received: " << pkt.getHeader().options << endl;
00227   }
00228 }
00229 
00230 void Session::getSingleAttributeSerializable(EIP_USINT class_id, EIP_USINT instance_id,
00231   EIP_USINT attribute_id, Serializable& result)
00232 {
00233   shared_ptr<Serializable> no_data;
00234   RRDataResponse resp_data = sendRRDataCommand(0x0E,
00235     Path(class_id, instance_id, attribute_id), no_data);
00236 
00237   resp_data.getResponseDataAs(result);
00238 }
00239 
00240 void Session::setSingleAttributeSerializable(EIP_USINT class_id,
00241   EIP_USINT instance_id, EIP_USINT attribute_id, shared_ptr<Serializable> data)
00242 {
00243   RRDataResponse resp_data = sendRRDataCommand(0x10,
00244     Path(class_id, instance_id, attribute_id), data);
00245 }
00246 
00247 RRDataResponse Session::sendRRDataCommand(EIP_USINT service, const Path& path,
00248   shared_ptr<Serializable> data)
00249 {
00250   cout << "Creating RR Data Request" << endl;
00251   shared_ptr<RRDataRequest> req_data =
00252     make_shared<RRDataRequest> (service, path, data);
00253   EncapPacket encap_pkt(EIP_CMD_SEND_RR_DATA, session_id_, req_data);
00254 
00255   // send command and get response
00256   EncapPacket response;
00257   try
00258   {
00259     response = sendCommand(encap_pkt);
00260   }
00261   catch (std::length_error ex)
00262   {
00263     cerr << "Response packet to RR command too short: " << ex.what() << endl;
00264     throw std::runtime_error("Packet response to RR Data Command too short");
00265   }
00266   catch (std::logic_error ex)
00267   {
00268     cerr << "Invalid response to RR command: " << ex.what() << endl;
00269     throw std::runtime_error("Invalid packet response to RR Data Command");
00270   }
00271 
00272   RRDataResponse resp_data;
00273   try
00274   {
00275     response.getPayloadAs(resp_data);
00276   }
00277   catch (std::length_error ex)
00278   {
00279     cerr << "Response data to RR command too short: " << ex.what() << endl;
00280     throw std::runtime_error("Response data to RR Command too short");
00281   }
00282   catch (std::logic_error ex)
00283   {
00284     cerr << "Invalid data to RR command: " << ex.what() << endl;
00285     throw std::runtime_error("Invalid data in response to RR command");
00286   }
00287 
00288   // check that responses are valid
00289   if (resp_data.getServiceCode() != (service | 0x80))
00290   {
00291     cerr << "Warning: Wrong service code returned for RR Data command. Expected: "
00292       << (int)service << " but received " << (int)resp_data.getServiceCode() << endl;
00293     // throw std::runtime_error("Wrong service code returned for RR Data command");
00294   }
00295   if (resp_data.getGeneralStatus())
00296   {
00297     cerr << "RR Data Command failed with status " << (int)resp_data.getGeneralStatus() << endl;
00298     throw std::runtime_error("RR Data Command Failed");
00299   }
00300   return resp_data;
00301 }
00302 
00303 int Session::createConnection(const EIP_CONNECTION_INFO_T& o_to_t,
00304   const EIP_CONNECTION_INFO_T& t_to_o)
00305 {
00306   Connection conn(o_to_t, t_to_o);
00307   conn.originator_vendor_id = my_vendor_id_;
00308   conn.originator_sn = my_serial_num_;
00309   conn.connection_sn = next_connection_sn_++;
00310   conn.o_to_t_connection_id = next_connection_id_++;
00311   conn.t_to_o_connection_id = next_connection_id_++;
00312 
00313   shared_ptr<ForwardOpenRequest> req = conn.createForwardOpenRequest();
00314   RRDataResponse resp_data = sendRRDataCommand(0x5B, Path(0x06, 1), req);
00315   ForwardOpenSuccess result;
00316   resp_data.getResponseDataAs(result);
00317   if (!conn.verifyForwardOpenResult(result))
00318   {
00319     cerr << "Received invalid response to forward open request" << endl;
00320     throw std::logic_error("Forward Open Response Invalid");
00321   }
00322 
00323   connections_.push_back(conn);
00324   return connections_.size() - 1;
00325 }
00326 
00327 void Session::closeConnection(size_t n)
00328 {
00329   shared_ptr<ForwardCloseRequest> req = connections_[n].createForwardCloseRequest();
00330   RRDataResponse resp_data = sendRRDataCommand(0x4E, Path(0x06, 1), req);
00331   ForwardCloseSuccess result;
00332   resp_data.getResponseDataAs(result);
00333   if (!connections_[n].verifyForwardCloseResult(result))
00334   {
00335     cerr << "Received invalid response to forward close request" << endl;
00336     throw std::logic_error("Forward Close Response Invalid");
00337   }
00338   // remove the connection from the list
00339   connections_.erase(connections_.begin() + n);
00340 }
00341 
00342 CPFPacket Session::receiveIOPacket()
00343 {
00344   // cout << "Receiving IO packet" << endl;
00345   size_t n = io_socket_->receive(buffer(recv_buffer_));
00346   // cout << "Received IO of " << n << " bytes" << endl;
00347 
00348   BufferReader reader(buffer(recv_buffer_, n));
00349   CPFPacket result;
00350   result.deserialize(reader);
00351 
00352   if (reader.getByteCount() != n)
00353   {
00354     cerr << "Warning: IO packet received with " << n <<
00355       " bytes, but only " << reader.getByteCount() << " bytes used" << endl;
00356   }
00357 
00358   return result;
00359 }
00360 
00361 void Session::sendIOPacket(CPFPacket& pkt)
00362 {
00363   // cout << "Sending CPF Packet on IO Socket" << endl;
00364   io_socket_->send(pkt);
00365 }
00366 
00367 
00368 } // namespace eip


odva_ethernetip
Author(s): Kareem Shehata
autogenerated on Sat Jun 8 2019 20:21:23