test_emcy.cpp
Go to the documentation of this file.
00001 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
00002 
00003 // -- BEGIN LICENSE BLOCK ----------------------------------------------
00004 // This file is part of the SCHUNK Canopen Driver suite.
00005 //
00006 // This program is free software licensed under the LGPL
00007 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
00008 // You can find a copy of this license in LICENSE folder in the top
00009 // directory of the source code.
00010 //
00011 // © Copyright 2016 SCHUNK GmbH, Lauffen/Neckar Germany
00012 // © Copyright 2016 FZI Forschungszentrum Informatik, Karlsruhe, Germany
00013 // -- END LICENSE BLOCK ------------------------------------------------
00014 
00015 //----------------------------------------------------------------------
00022 //----------------------------------------------------------------------
00023 
00024 #include <icl_hardware_can/tCanDeviceDummy.h>
00025 
00026 #include <icl_hardware_canopen/CanOpenController.h>
00027 #include <icl_hardware_canopen/DS301Group.h>
00028 #include <icl_hardware_canopen/SDO.h>
00029 
00030 #include <icl_hardware_canopen/Logging.h>
00031 
00032 #include <boost/test/included/unit_test.hpp>
00033 
00034 
00035 using namespace icl_hardware::canopen_schunk;
00036 BOOST_AUTO_TEST_SUITE( ts_emcy )
00037 
00038 /*
00039  * This test tests the basic EMCY functionality. One example message is sent and compared to what
00040  * arrives at the node.
00041  * Additionally, some artificially false data is tested for error handling.
00042  */
00043 BOOST_AUTO_TEST_CASE( message_parsing )
00044 {
00045   // Initializing
00046   icl_core::logging::initialize();
00047   icl_core::logging::setLogLevel(icl_core::logging::eLL_TRACE);
00048   LOGGING_INFO(CanOpen, "---------------------------" << endl <<
00049                         "-----Running EMCY test-----" << endl <<
00050                         "---------------------------" << endl);
00051 
00052   CanOpenController my_controller("Dummy");
00053   boost::shared_ptr<icl_hardware::can::tCanDeviceDummy> can_device;
00054   can_device = boost::dynamic_pointer_cast<icl_hardware::can::tCanDeviceDummy>(my_controller.getCanDevice());
00055 
00056   // Add one node
00057   my_controller.addGroup<DS301Group>("testgroup");
00058   my_controller.addNode<DS301Node>(1, "testgroup");
00059   DS301Group::Ptr my_group = my_controller.getGroup<DS301Group>("testgroup");
00060   DS301Node::Ptr node = my_group->getNodes().front();
00061 
00062   // create can message
00063   CanMsg msg;
00064   msg.id = ds301::ID_EMCY_MIN; // EMCY for first node
00065   msg.dlc = 8;
00066   msg.rtr = 0;
00067   // error code 0x8130
00068   msg.data[0] = 0x30;
00069   msg.data[1] = 0x81;
00070   // Error registers 0x01, 0x02, 0x03, 0x20
00071   msg.data[2] = 0x27;
00072 
00073   // some arbitrary manufacturer-specific data
00074   msg.data[3] = 0x03;
00075   msg.data[4] = 0x04;
00076   msg.data[5] = 0x05;
00077   msg.data[6] = 0x06;
00078   msg.data[7] = 0x07;
00079   can_device->addResponse(msg, false);
00080 
00081   // wait for the response being processed
00082   boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00083 
00084   uint16_t eec_ret;
00085   uint8_t error_register_ret;
00086   std::vector<uint8_t> msef_ret;
00087   BOOST_REQUIRE( node->m_emcy->getErrorInformation(eec_ret, error_register_ret, msef_ret));
00088 
00089   BOOST_REQUIRE( eec_ret == msg.data[0] + (msg.data[1] << 8) );
00090   BOOST_REQUIRE( error_register_ret == msg.data[2]);
00091   BOOST_REQUIRE( msef_ret[0] == msg.data[3]);
00092   BOOST_REQUIRE( msef_ret[1] == msg.data[4]);
00093   BOOST_REQUIRE( msef_ret[2] == msg.data[5]);
00094   BOOST_REQUIRE( msef_ret[3] == msg.data[6]);
00095   BOOST_REQUIRE( msef_ret[4] == msg.data[7]);
00096   BOOST_REQUIRE( node->m_emcy->getEmcyStatus() == EMCY::EMCY_STATE_ERROR_OCCURED);
00097 
00098   // send a ERROR_FREE_EMCY
00099   msg.data[0] = 0x00;
00100   msg.data[1] = 0x00;
00101 
00102   can_device->addResponse(msg, false);
00103 
00104   // wait for the response being processed
00105   boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00106 
00107   // Now there should be no error
00108   BOOST_REQUIRE( !(node->m_emcy->getErrorInformation(eec_ret, error_register_ret, msef_ret)));
00109   BOOST_REQUIRE( node->m_emcy->getEmcyStatus() == EMCY::EMCY_STATE_ERROR_FREE);
00110   std::cout << "\n";
00111 
00112   // WARNING: Do not remove the following 4 lines as they reset the error state to non-error. Otherwise the following tests will fail!
00113   // send a ERROR_FREE_EMCY
00114   msg.data[0] = 0x00;
00115   msg.data[1] = 0x00;
00116   can_device->addResponse(msg, false);
00117   boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00118 
00119   msg.dlc = 13; // some arbitrary illegal number
00120   can_device->addResponse(msg, false);
00121   BOOST_REQUIRE( !(node->m_emcy->getErrorInformation(eec_ret, error_register_ret, msef_ret)));
00122   BOOST_REQUIRE( node->m_emcy->getEmcyStatus() == EMCY::EMCY_STATE_ERROR_FREE);
00123   msg.dlc = 8;
00124   boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00125   std::cout << "\n";
00126 
00127   msg.id = ds301::ID_EMCY_MIN + 1; // This node id does not exist
00128   can_device->addResponse(msg, false);
00129   BOOST_REQUIRE( !(node->m_emcy->getErrorInformation(eec_ret, error_register_ret, msef_ret)));
00130   BOOST_REQUIRE( node->m_emcy->getEmcyStatus() == EMCY::EMCY_STATE_ERROR_FREE);
00131   msg.id = ds301::ID_EMCY_MIN;
00132   boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00133   std::cout << "\n";
00134 
00135 }
00136 
00137 
00138 BOOST_AUTO_TEST_SUITE_END()


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Thu Jun 6 2019 20:17:24