cod_decod_manager.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Shadow Robot Company, All rights reserved.
00003  * 
00004  * This library is free software; you can redistribute it and/or
00005  * modify it under the terms of the GNU Lesser General Public
00006  * License as published by the Free Software Foundation; either
00007  * version 3.0 of the License, or (at your option) any later version.
00008  * 
00009  * This library is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00012  * Lesser General Public License for more details.
00013  * 
00014  * You should have received a copy of the GNU Lesser General Public
00015  * License along with this library.
00016  */
00017 
00028 #include "sr_ronex_drivers/cod_decod/cod_decod_manager.hpp"
00029 #include "sr_ronex_drivers/cod_decod/cod_decod_std_io.hpp"
00030 #include <boost/foreach.hpp>
00031 #include <boost/regex.hpp>
00032 #include <string>
00033 #include <vector>
00034 
00035 namespace sr_cod_decod
00036 {
00037 
00038   CodDecodManager::CodDecodManager(hardware_interface::HardwareInterface *hw, EtherCAT_SlaveHandler *sh,
00039   int n_digital_outputs, int n_analog_outputs, int n_digital_inputs, int n_analog_inputs, int n_PWM_outputs)
00040     :cod_decod_loader_("sr_ronex_drivers", "sr_cod_decod::CodDecod")
00041   {
00042     uint32_t product_code = sh->get_product_code();
00043     uint32_t serial = sh->get_serial();
00044     uint32_t revision = sh->get_revision();
00045     uint32_t slave = sh->get_station_address()-1;
00046 
00047     // The point of this code to find a cod_decod class whose name matches the EtherCAT product ID and Serial Number
00048     // for a given device.
00049     // Thus cod_decod plugins would register themselves with PLUGINLIB_EXPORT_CLASS
00050     //
00051     //   PLUGINLIB_EXPORT_CLASS(class_namespace::class_type, base_class_namespace::base_class_type)
00052     //
00053     // For the CodDecodExample cod_decod example module to be use with e.g productID = 87032868 and serialNumber = 21,
00054     // this statement would look something like:
00055     //
00056     //  PLUGINLIB_EXPORT_CLASS(sr_cod_decod::CodDecodExample, sr_cod_decod::CodDecod);
00057     //
00058     //
00059     // Unfortunately, we don't know which ROS package a particular cod_decod class is defined in.
00060     // To account for this, we search through the list of class names, one-by-one and find string where
00061     // last part of string matches product ID and serial number of a device.
00062     stringstream class_name_regex_str;
00063     class_name_regex_str << "(.*/)?" << product_code << "_" << serial;
00064     boost::regex class_name_regex(class_name_regex_str.str(), boost::regex::extended);
00065 
00066     std::vector<std::string> classes = cod_decod_loader_.getDeclaredClasses();
00067     std::string matching_class_name;
00068 
00069     BOOST_FOREACH(const std::string &class_name, classes)
00070     {
00071       if (regex_match(class_name, class_name_regex))
00072       {
00073         if (matching_class_name.size() != 0)
00074         {
00075           ROS_ERROR("Found more than 1 CodDecod class for device with product code : %u (0x%X) and serial number : "
00076           "%u (0x%X)", product_code, product_code, serial, serial);
00077           ROS_ERROR("First class name = '%s'.  Second class name = '%s'",
00078                     class_name.c_str(), matching_class_name.c_str());
00079         }
00080         matching_class_name = class_name;
00081       }
00082     }
00083 
00084     if (matching_class_name.size() != 0)
00085     {
00086       // ROS_WARN("Using driver class '%s' for device with product code %d",
00087       //         matching_class_name.c_str(), product_code);
00088       try
00089       {
00090         cod_decod_ = cod_decod_loader_.createInstance(matching_class_name);
00091       }
00092       catch (pluginlib::LibraryLoadException &e)
00093       {
00094         cod_decod_.reset();
00095         ROS_FATAL("Unable to load CodDecod plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), "
00096         "revision: %d (0x%X)",
00097                   slave, product_code, product_code, serial, serial, revision, revision);
00098         ROS_FATAL("%s", e.what());
00099       }
00100     }
00101     else
00102     {
00103       ROS_INFO("Unable to find a dedicated CodDecod plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), "
00104       "revision: %d (0x%X)",
00105                 slave, product_code, product_code, serial, serial, revision, revision);
00106       ROS_INFO("Possible classes:");
00107       BOOST_FOREACH(const std::string &class_name, classes)
00108       {
00109         ROS_INFO("  %s", class_name.c_str());
00110       }
00111       ROS_INFO("Loading the default CodDecod plugin: CodDecodStdIo");
00112       try
00113       {
00114         cod_decod_ = cod_decod_loader_.createInstance("sr_ronex_drivers/87032868_0");
00115       }
00116       catch (pluginlib::LibraryLoadException &e)
00117       {
00118         cod_decod_.reset();
00119         ROS_FATAL("Unable to load CodDecod plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), "
00120         "revision: %d (0x%X)",
00121                   slave, product_code, product_code, serial, serial, revision, revision);
00122         ROS_FATAL("%s", e.what());
00123       }
00124     }
00125 
00126     if (cod_decod_ != NULL)
00127     {
00128       cod_decod_->construct(hw, sh, n_digital_outputs, n_analog_outputs, n_digital_inputs, n_analog_inputs,
00129       n_PWM_outputs);
00130     }
00131   }
00132 
00133   void CodDecodManager::update(unsigned char *status_buffer)
00134   {
00135     if (cod_decod_)
00136     {
00137       cod_decod_->update(status_buffer);
00138     }
00139   }
00140 
00141   void CodDecodManager::build_command(unsigned char *command_buffer)
00142   {
00143     if (cod_decod_)
00144     {
00145       cod_decod_->build_command(command_buffer);
00146     }
00147   }
00148 
00149 }  // namespace sr_cod_decod


sr_ronex_drivers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Thu Jun 6 2019 21:22:00