CanOpenController.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 //----------------------------------------------------------------------
00023 //----------------------------------------------------------------------
00024 
00025 #include "CanOpenController.h"
00026 #include <icl_hardware_can/tCanDeviceDummy.h>
00027 #include "Logging.h"
00028 #include "ds301.h"
00029 #include "sync.h"
00030 #include "exceptions.h"
00031 
00032 #include <cstdlib> // getenv
00033 #include <dirent.h>
00034 #include <boost/filesystem.hpp>
00035 #include <boost/regex.hpp>
00036 
00037 namespace icl_hardware {
00038 namespace canopen_schunk {
00039 
00040 CanOpenController::CanOpenController(const std::string can_device_identifier,
00041                                      const uint32_t baud_rate,
00042                                      const std::string& resource_folder_location
00043                                     )
00044   : m_can_device_name(can_device_identifier),
00045     m_can_device_flags(O_RDWR|O_NONBLOCK),
00046     m_can_device_acceptance_code(0xff),
00047     m_can_device_acceptance_mask(0xff),
00048     m_can_device_send_fifo_size(300),
00049     m_can_device_receive_fifo_size(2000),
00050     m_can_device_baud_rate(baud_rate),
00051     m_heartbeat_monitor(new HeartBeatMonitor()),
00052     m_polling_period_ms(1),
00053     m_resource_folder_location(resource_folder_location),
00054     m_ws_broadcast_counter(0),
00055     m_ws_broadcast_rate(5)
00056 {
00057     init();
00058 }
00059 
00060 CanOpenController::~CanOpenController ()
00061 {
00062   // Stop receiving thread
00063   if (m_receive_thread)
00064   {
00065     m_receive_thread->stop();
00066   }
00067 }
00068 
00069 void CanOpenController::initNodes (const int16_t node_id)
00070 {
00071   for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin(); it != m_nodes.end(); ++it)
00072   {
00073     if (it->first == node_id || node_id < 0)
00074     {
00075       it->second->initNode();
00076     }
00077   }
00078 }
00079 
00080 void CanOpenController::processCanMsgCallback ( const can::tCanMessage& msg )
00081 {
00082   if (msg.id == ds301::ID_NMT)
00083   {
00084     LOGGING_DEBUG_C (CanOpen, CanOpenController, "NMT MESSAGE RECEIVED" << endl);
00085     LOGGING_TRACE_C (CanOpen, CanOpenController,
00086                      "Message id: " << msg.id << endl
00087                      << "Message length: " << msg.dlc << endl
00088                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00089   }
00090   else if (msg.id == ds301::ID_SYNC)
00091   {
00092     LOGGING_DEBUG_C (CanOpen, CanOpenController, "SYNC MESSAGE RECEIVED" << endl);
00093     LOGGING_TRACE_C (CanOpen, CanOpenController,
00094                      "Message id: " << msg.id << endl
00095                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00096   }
00097   else if (msg.id >= ds301::ID_EMCY_MIN && msg.id <= ds301::ID_EMCY_MAX)
00098   {
00099     LOGGING_DEBUG_C (CanOpen, CanOpenController, "EMCY MESSAGE RECEIVED" << endl);
00100     LOGGING_TRACE_C (CanOpen, CanOpenController,
00101                      "Message id: " << msg.id << endl
00102                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00103     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_EMCY_MIN+1);
00104     if (node)
00105     {
00106       try
00107       {
00108         node->m_emcy->update(msg);
00109       }
00110       catch (const std::exception& e)
00111       {
00112         LOGGING_ERROR (CanOpen, "Exception thrown in EMCY update function: " << e.what() << endl);
00113       }
00114     }
00115   }
00116   else if (msg.id == ds301::ID_TIME)
00117   {
00118     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TIME MESSAGE RECEIVED" << endl);
00119     LOGGING_TRACE_C (CanOpen, CanOpenController,
00120                      "Message id: " << msg.id << endl
00121                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00122   }
00123   else if (msg.id >= ds301::ID_TPDO1_MIN && msg.id <= ds301::ID_TPDO1_MAX)
00124   {
00125     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO1 MESSAGE for node " << msg.id - ds301::ID_TPDO1_MIN+1 << " RECEIVED" << endl);
00126     LOGGING_TRACE_C (CanOpen, CanOpenController,
00127                      "Message id: " << msg.id << endl
00128                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00129     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_TPDO1_MIN+1);
00130     if (node)
00131     {
00132       try
00133       {
00134         node->m_tpdos.at(0)->update(msg);
00135       }
00136       catch (const std::exception& e)
00137       {
00138         LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
00139       }
00140     }
00141   }
00142   else if (msg.id >= ds301::ID_RPDO1_MIN && msg.id <= ds301::ID_RPDO1_MAX)
00143   {
00144     LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO1 MESSAGE RECEIVED" << endl);
00145     LOGGING_TRACE_C (CanOpen, CanOpenController,
00146                      "Message id: " << msg.id << endl
00147                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00148   }
00149   else if (msg.id >= ds301::ID_TPDO2_MIN && msg.id <= ds301::ID_TPDO2_MAX)
00150   {
00151     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO2 MESSAGE RECEIVED" << endl);
00152     LOGGING_TRACE_C (CanOpen, CanOpenController,
00153                      "Message id: " << msg.id << endl
00154                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00155     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_TPDO2_MIN+1);
00156     if (node)
00157     {
00158       try
00159       {
00160         node->m_tpdos.at(1)->update(msg);
00161       }
00162       catch (const std::exception& e)
00163       {
00164         LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
00165       }
00166     }
00167   }
00168   else if (msg.id >= ds301::ID_RPDO2_MIN && msg.id <= ds301::ID_RPDO2_MAX)
00169   {
00170     LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO2 MESSAGE RECEIVED" << endl);
00171     LOGGING_TRACE_C (CanOpen, CanOpenController,
00172                      "Message id: " << msg.id << endl
00173                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00174   }
00175   else if (msg.id >= ds301::ID_TPDO3_MIN && msg.id <= ds301::ID_TPDO3_MAX)
00176   {
00177     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO3 MESSAGE RECEIVED" << endl);
00178     LOGGING_TRACE_C (CanOpen, CanOpenController,
00179                      "Message id: " << msg.id << endl
00180                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00181     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_TPDO3_MIN+1);
00182     if (node)
00183     {
00184       try
00185       {
00186         node->m_tpdos.at(2)->update(msg);
00187       }
00188       catch (const std::exception& e)
00189       {
00190         LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
00191       }
00192     }
00193   }
00194   else if (msg.id >= ds301::ID_RPDO3_MIN && msg.id <= ds301::ID_RPDO3_MAX)
00195   {
00196     LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO3 MESSAGE RECEIVED" << endl);
00197     LOGGING_TRACE_C (CanOpen, CanOpenController,
00198                      "Message id: " << msg.id << endl
00199                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00200   }
00201   else if (msg.id >= ds301::ID_TPDO4_MIN && msg.id <= ds301::ID_TPDO4_MAX)
00202   {
00203     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO4 MESSAGE RECEIVED" << endl);
00204     LOGGING_TRACE_C (CanOpen, CanOpenController,
00205                      "Message id: " << msg.id << endl
00206                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00207     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_TPDO4_MIN+1);
00208     if (node)
00209     {
00210       try
00211       {
00212         node->m_tpdos.at(3)->update(msg);
00213       }
00214       catch (const std::exception& e)
00215       {
00216         LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
00217       }
00218     }
00219   }
00220   else if (msg.id >= ds301::ID_RPDO4_MIN && msg.id <= ds301::ID_RPDO4_MAX)
00221   {
00222     LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO4 MESSAGE RECEIVED" << endl);
00223     LOGGING_TRACE_C (CanOpen, CanOpenController,
00224                      "Message id: " << msg.id << endl
00225                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00226   }
00227   else if (msg.id >= ds301::ID_TSDO_MIN && msg.id <= ds301::ID_TSDO_MAX)
00228   {
00229     LOGGING_DEBUG_C (CanOpen, CanOpenController, "TSDO MESSAGE RECEIVED" << endl);
00230     LOGGING_TRACE_C (CanOpen, CanOpenController,
00231                      "Message id: " << msg.id << endl
00232                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00233     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_TSDO_MIN+1);
00234     if (node)
00235     {
00236       try
00237       {
00238         node->m_sdo.update(msg);
00239       }
00240       catch (const ResponseException& e)
00241       {
00242         LOGGING_ERROR (CanOpen, "Exception thrown in SDO update function: " << e.what() << endl);
00243       }
00244     }
00245   }
00246   else if (msg.id >= ds301::ID_RSDO_MIN && msg.id <= ds301::ID_RSDO_MAX)
00247   {
00248     LOGGING_DEBUG_C (CanOpen, CanOpenController, "RSDO MESSAGE RECEIVED" << endl);
00249     LOGGING_TRACE_C (CanOpen, CanOpenController,
00250                      "Message id: " << msg.id << endl
00251                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00252     DS301Node::Ptr node = getNodeById(msg.id - ds301::ID_RSDO_MIN+1);
00253     if (node)
00254     {
00255       try
00256       {
00257         node->m_sdo.update(msg);
00258       }
00259       catch (const ResponseException& e)
00260       {
00261         LOGGING_ERROR (CanOpen, "Exception thrown in SDO update function: " << e.what() << endl);
00262       }
00263     }
00264   }
00265   else if (msg.id >= ds301::ID_NMT_ERROR_MIN && msg.id <= ds301::ID_NMT_ERROR_MAX)
00266   {
00267     LOGGING_DEBUG_C (CanOpen, CanOpenController, "NMT_ERROR MESSAGE RECEIVED" << endl);
00268     LOGGING_TRACE_C (CanOpen, CanOpenController,
00269                      "Message id: " << msg.id << endl
00270                      << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
00271     uint8_t node_id = msg.id - ds301::ID_NMT_ERROR_MIN+1;
00272     DS301Node::Ptr node = getNodeById(node_id);
00273 
00274     if (node)
00275     {
00276       try
00277       {
00278         node->m_nmt.update(msg);
00279       }
00280       catch (const ResponseException& e)
00281       {
00282         LOGGING_ERROR (CanOpen, "Exception thrown in NMT update function: " << e.what() << endl);
00283       }
00284       if (msg.data[0] != 0x0)
00285       {
00286         m_heartbeat_monitor->addHeartbeat(node_id);
00287       }
00288     }
00289     else if ( msg.dlc == 1 && msg.data[0] == 0x0)
00290     {
00291       // TODO (optional): If byte 0: add new node (autodiscovery)
00292       LOGGING_INFO_C (CanOpen, CanOpenController, "NMT bootup of node " << msg.id - ds301::ID_NMT_ERROR_MIN+1 << endl);
00293     }
00294   }
00295 }
00296 
00297 void CanOpenController::reconnectCanDevice(const std::string& can_identifier, const uint32_t baud_rate)
00298 {
00299   if (baud_rate != 0)
00300   {
00301     m_can_device_baud_rate = baud_rate;
00302   }
00303   m_can_device_name = can_identifier;
00304 
00305   if (m_receive_thread)
00306   {
00307     m_receive_thread->stop();
00308   }
00309 
00310   try
00311   {
00312     init();
00313   }
00314   catch (const DeviceException& e)
00315   {
00316     LOGGING_ERROR_C (CanOpen, CanOpenController, "Initializing device failed. Reason: " << e.what());
00317   }
00318 }
00319 
00320 void CanOpenController::init()
00321 {
00322   #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
00323   m_ws_broadcaster = boost::shared_ptr<icl_comm::websocket::WsBroadcaster>(new icl_comm::websocket::WsBroadcaster(icl_comm::websocket::WsBroadcaster::eRT_LWA4P));
00324   #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
00325 
00326 
00327   getResources();
00328 
00329   if (m_can_device_name == "Dummy")
00330   {
00331     m_can_device.reset(new icl_hardware::can::tCanDeviceDummy( m_can_device_name.c_str(),
00332                                                             m_can_device_flags,
00333                                                             m_can_device_acceptance_code,
00334                                                             m_can_device_acceptance_mask,
00335                                                             m_can_device_baud_rate,
00336                                                             m_can_device_send_fifo_size,
00337                                                             m_can_device_receive_fifo_size
00338                                                           ));
00339   }
00340   else if (m_can_device_name == "auto")
00341   {
00342     std::vector<std::string> names;
00343     boost::regex pattern("pcan(usb|pci)\\d+");
00344 
00345     DIR* dir;
00346     struct dirent* ent;
00347     if ((dir = opendir("/dev")) != NULL)
00348     {
00349       /* print all the files and directories within directory */
00350       while ((ent = readdir(dir)) != NULL)
00351       {
00352         std::string s = ent->d_name;
00353         if (boost::regex_match(s, pattern))
00354         {
00355           names.push_back("/dev/" + s);
00356           LOGGING_INFO(CanOpen, "Found " << s << endl);
00357         }
00358       }
00359       closedir(dir);
00360     }
00361 
00362     bool can_found = false;
00363     LOGGING_INFO (CanOpen, "CAN Device was set to auto. " << endl);
00364 
00365     for (size_t num = 0; num < names.size() ; ++num)
00366     {
00367         m_can_device_name = names[num];
00368         LOGGING_INFO(CanOpen, "Trying CAN device: " << m_can_device_name << "... " << endl);
00369         try
00370         {
00371             m_can_device.reset(icl_hardware::can::tCanDevice::Create( m_can_device_name.c_str(),
00372                                                                       m_can_device_flags,
00373                                                                       m_can_device_acceptance_code,
00374                                                                       m_can_device_acceptance_mask,
00375                                                                       m_can_device_baud_rate,
00376                                                                       m_can_device_send_fifo_size,
00377                                                                       m_can_device_receive_fifo_size
00378                                                                     ));
00379 
00380             if (m_can_device)
00381             {
00382               if (!m_can_device->IsInitialized())
00383               {
00384                 std::stringstream ss;
00385                 continue;
00386               }
00387             }
00388             can_found = true;
00389 
00390             break;
00391 
00392         }
00393         catch (DeviceException const& e)
00394         {
00395             LOGGING_INFO(CanOpen, e.what() << endl);
00396             can_found = false;
00397         }
00398     }
00399     if (!can_found)
00400     {
00401         LOGGING_ERROR(CanOpen, " CAN DEVICE COULD NOT BE OPENED. \n >> Giving up.");
00402         exit(-123);
00403         return;
00404     }
00405   }
00406   else
00407   {
00408     m_can_device.reset(icl_hardware::can::tCanDevice::Create( m_can_device_name.c_str(),
00409                                                             m_can_device_flags,
00410                                                             m_can_device_acceptance_code,
00411                                                             m_can_device_acceptance_mask,
00412                                                             m_can_device_baud_rate,
00413                                                             m_can_device_send_fifo_size,
00414                                                             m_can_device_receive_fifo_size
00415                                                           ));
00416   }
00417 
00418   if (m_can_device)
00419   {
00420     if (!m_can_device->IsInitialized())
00421     {
00422       std::stringstream ss;
00423       ss << "FATAL: COULD NOT INITIALIZE CAN DEVICE in " << m_can_device_name;
00424 
00425       throw DeviceException(ss.str());
00426     }
00427   }
00428   else
00429   {
00430     std::stringstream ss;
00431     ss << "FATAL: COULD NOT GET VALID CAN DEVICE in " << m_can_device_name;
00432 
00433     throw DeviceException(ss.str());
00434   }
00435 
00436   m_receive_thread.reset(new CanOpenReceiveThread(icl_core::TimeSpan::createFromMSec(m_polling_period_ms),
00437                                                   m_can_device,
00438                                                   boost::bind(&CanOpenController::processCanMsgCallback, this, _1)
00439                                                  ));
00440 
00441   if (!m_receive_thread)
00442   {
00443     throw DeviceException("FATAL: Could not start listener thread for CAN bus.");
00444   }
00445 
00446   // add default DS402Group
00447   addGroup<DS402Group>("default");
00448   m_heartbeat_monitor->registerErrorCallback(boost::bind(&CanOpenController::stopAll, this));
00449 }
00450 
00451 void CanOpenController::deleteGroup(const std::string& identifier)
00452 {
00453   std::string sanitized_identifier = sanitizeString(identifier);
00454 
00455   std::map<std::string, DS301Group::Ptr>::iterator group_it;
00456   group_it = m_groups.find(sanitized_identifier);
00457   if (group_it != m_groups.end())
00458   {
00459     std::vector<uint8_t> deleted_node_ids;
00460     group_it->second->deleteNodes(deleted_node_ids); // This will return the IDs of deleted nodes
00461 
00462     // Now also delete shared pointers in controller
00463     for (std::vector<uint8_t>::iterator it = deleted_node_ids.begin();
00464          it != deleted_node_ids.end();
00465          ++it)
00466     {
00467       // Find the node with given Id
00468       std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(*it);
00469       assert(node_it->second.use_count() == 1);
00470       m_nodes.erase(node_it);
00471     }
00472 
00473     m_groups.erase(group_it);
00474   }
00475   else
00476   {
00477     LOGGING_ERROR_C(CanOpen, CanOpenController, "No group with the given identifer " << sanitized_identifier
00478       << " exists. Not deleting anything." << endl);
00479   }
00480 }
00481 
00482 void CanOpenController::deleteNode(const uint8_t node_id)
00483 {
00484   // Delete node in group
00485   for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
00486        it != m_groups.end();
00487        ++it)
00488   {
00489     if (it->second->deleteNodeFromId(node_id))
00490     {
00491       // group for node_id was found and node was deleted.
00492       break;
00493     }
00494   }
00495 
00496   // Delete node in controller's list
00497   std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(node_id);
00498   assert(node_it->second.use_count() == 1);
00499   m_nodes.erase(node_it);
00500 }
00501 
00502 DS301Node::Ptr CanOpenController::getNodeById(const uint8_t node_id)
00503 {
00504   std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(node_id);
00505   if (node_it == m_nodes.end())
00506   {
00507     LOGGING_ERROR_C(CanOpen, CanOpenController, "A node with the given ID " << node_id <<
00508                                                 " does not exist. Therefore this CAN message will be ignored." << endl);
00509     // Return a NULL pointer
00510     return DS301Node::Ptr();
00511   }
00512   return node_it->second;
00513 }
00514 
00515 void CanOpenController::getResources()
00516 {
00517   boost::filesystem::path resources_path(m_resource_folder_location);
00518 
00519   if (m_resource_folder_location == "")
00520   {
00521     char const* tmp = std::getenv("CANOPEN_RESOURCE_PATH");
00522     if (tmp == NULL)
00523     {
00524       LOGGING_WARNING_C(
00525           CanOpen,
00526           CanOpenController,
00527           "The environment variable 'CANOPEN_RESOURCE_PATH' could not be read. Using relative path 'resources/'" << endl);
00528       resources_path = boost::filesystem::path("resources");
00529     }
00530     else
00531     {
00532       resources_path = boost::filesystem::path(tmp);
00533     }
00534   }
00535 
00536   std::string sdo_errors_filename = (resources_path / boost::filesystem::path("SDO.ini")).string();
00537   SDO::addErrorMapFromFile( sdo_errors_filename );
00538 
00539   std::string emcy_emergency_errors_filename = (resources_path / boost::filesystem::path("EMCY.ini")).string();
00540   EMCY::addEmergencyErrorMap( emcy_emergency_errors_filename, "emergency_errors");
00541   EMCY::addErrorRegisterMap( emcy_emergency_errors_filename, "error_registers");
00542 
00543   emcy_emergency_errors_filename = (resources_path / boost::filesystem::path("EMCY_DS402.ini")).string();
00544   EMCY::addEmergencyErrorMap( emcy_emergency_errors_filename, "emergency_errors");
00545 }
00546 
00547 void CanOpenController::syncAll()
00548 {
00549   for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
00550        it != m_nodes.end();
00551   ++it)
00552   {
00553     it->second->downloadPDOs();
00554   }
00555 
00556   sendSync (m_can_device);
00557 
00558   for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
00559        it != m_nodes.end();
00560   ++it)
00561   {
00562     it->second->uploadPDOs();
00563   }
00564 
00565   #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
00566   if(m_ws_broadcast_counter % m_ws_broadcast_rate == 0)
00567   {
00568     if (!m_ws_broadcaster->sendState())
00569     {
00570     //    LOGGING_WARNING_C(
00571     //        CanOpen,
00572     //        CanOpenController, "Can't send ws_broadcaster state - reconnect pending..." << endl);
00573     }
00574     m_ws_broadcast_counter = 0;
00575   }
00576   ++m_ws_broadcast_counter;
00577   #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
00578 
00579 }
00580 
00581 void CanOpenController::stopAll()
00582 {
00583   LOGGING_INFO (CanOpen, "Stop of all nodes requested!" << endl);
00584   for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
00585        it != m_nodes.end();
00586   ++it)
00587   {
00588     it->second->stopNode();
00589   }
00590 }
00591 
00592 std::vector< uint8_t > CanOpenController::getNodeList()
00593 {
00594   std::vector <uint8_t> node_list;
00595 
00596   size_t i=0;
00597   for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
00598        it != m_nodes.end();
00599   ++it)
00600   {
00601     it->second->downloadPDOs();
00602     node_list.push_back(it->second->getNodeId());
00603     ++i;
00604   }
00605 
00606   return node_list;
00607 }
00608 
00609 
00610 
00611 void CanOpenController::enablePPMotion(const int16_t node_id)
00612 {
00613   syncAll();
00614   usleep(5000); // sleep 5 ms
00615 
00616   LOGGING_TRACE_C (CanOpen, CanOpenController, "in function " << __FUNCTION__ << endl);
00617 
00618   for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
00619        it != m_groups.end();
00620        ++it)
00621   {
00622     DS402Group::Ptr group_ds402 = boost::dynamic_pointer_cast<DS402Group>(it->second);
00623     if (group_ds402)
00624     {
00625       group_ds402->startPPMovement(node_id);
00626     }
00627   }
00628 
00629   syncAll();
00630   usleep(5000); // sleep 5 ms
00631 
00632   for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
00633        it != m_groups.end();
00634        ++it)
00635   {
00636     DS402Group::Ptr group_ds402 = boost::dynamic_pointer_cast<DS402Group>(it->second);
00637     if (group_ds402)
00638     {
00639       group_ds402->acceptPPTargets(node_id);
00640     }
00641   }
00642   syncAll();
00643   usleep(5000); // sleep 5 ms
00644 
00645 }
00646 
00647 }}//end of NS


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