list_transports.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "image_transport/publisher_plugin.h"
00036 #include "image_transport/subscriber_plugin.h"
00037 #include <pluginlib/class_loader.h>
00038 #include <boost/foreach.hpp>
00039 #include <boost/algorithm/string/erase.hpp>
00040 #include <map>
00041 
00042 using namespace image_transport;
00043 using namespace pluginlib;
00044 
00045 enum PluginStatus {SUCCESS, CREATE_FAILURE, LIB_LOAD_FAILURE, DOES_NOT_EXIST};
00046 
00048 struct TransportDesc
00049 {
00050   TransportDesc()
00051     : pub_status(DOES_NOT_EXIST), sub_status(DOES_NOT_EXIST)
00052   {}
00053 
00054   std::string package_name;
00055   std::string pub_name;
00056   PluginStatus pub_status;
00057   std::string sub_name;
00058   PluginStatus sub_status;
00059 };
00061 
00062 int main(int argc, char** argv)
00063 {
00064   ClassLoader<PublisherPlugin> pub_loader("image_transport", "image_transport::PublisherPlugin");
00065   ClassLoader<SubscriberPlugin> sub_loader("image_transport", "image_transport::SubscriberPlugin");
00066   typedef std::map<std::string, TransportDesc> StatusMap;
00067   StatusMap transports;
00068 
00069   BOOST_FOREACH(const std::string& lookup_name, pub_loader.getDeclaredClasses()) {
00070     std::string transport_name = boost::erase_last_copy(lookup_name, "_pub");
00071     transports[transport_name].pub_name = lookup_name;
00072     transports[transport_name].package_name = pub_loader.getClassPackage(lookup_name);
00073     try {
00074       boost::shared_ptr<PublisherPlugin> pub = pub_loader.createInstance(lookup_name);
00075       transports[transport_name].pub_status = SUCCESS;
00076     }
00077     catch (const LibraryLoadException& e) {
00078       transports[transport_name].pub_status = LIB_LOAD_FAILURE;
00079     }
00080     catch (const CreateClassException& e) {
00081       transports[transport_name].pub_status = CREATE_FAILURE;
00082     }
00083   }
00084 
00085   BOOST_FOREACH(const std::string& lookup_name, sub_loader.getDeclaredClasses()) {
00086     std::string transport_name = boost::erase_last_copy(lookup_name, "_sub");
00087     transports[transport_name].sub_name = lookup_name;
00088     transports[transport_name].package_name = sub_loader.getClassPackage(lookup_name);
00089     try {
00090       boost::shared_ptr<SubscriberPlugin> sub = sub_loader.createInstance(lookup_name);
00091       transports[transport_name].sub_status = SUCCESS;
00092     }
00093     catch (const LibraryLoadException& e) {
00094       transports[transport_name].sub_status = LIB_LOAD_FAILURE;
00095     }
00096     catch (const CreateClassException& e) {
00097       transports[transport_name].sub_status = CREATE_FAILURE;
00098     }
00099   }
00100 
00101   bool problem_package = false;
00102   printf("Declared transports:\n");
00103   BOOST_FOREACH(const StatusMap::value_type& value, transports) {
00104     const TransportDesc& td = value.second;
00105     printf("%s", value.first.c_str());
00106     if ((td.pub_status == CREATE_FAILURE || td.pub_status == LIB_LOAD_FAILURE) ||
00107         (td.sub_status == CREATE_FAILURE || td.sub_status == LIB_LOAD_FAILURE)) {
00108       printf(" (*): Not available. Try 'catkin_make --pkg %s'.", td.package_name.c_str());
00109       problem_package = true;
00110     }
00111     printf("\n");
00112   }
00113 #if 0
00114   if (problem_package)
00115     printf("(*) \n");
00116 #endif
00117 
00118   printf("\nDetails:\n");
00119   BOOST_FOREACH(const StatusMap::value_type& value, transports) {
00120     const TransportDesc& td = value.second;
00121     printf("----------\n");
00122     printf("\"%s\"\n", value.first.c_str());
00123     if (td.pub_status == CREATE_FAILURE || td.sub_status == CREATE_FAILURE) {
00124       printf("*** Plugins are built, but could not be loaded. The package may need to be rebuilt or may not be compatible with this release of image_common. ***\n");
00125     }
00126     else if (td.pub_status == LIB_LOAD_FAILURE || td.sub_status == LIB_LOAD_FAILURE) {
00127       printf("*** Plugins are not built. ***\n");
00128     }
00129     printf(" - Provided by package: %s\n", td.package_name.c_str());
00130     if (td.pub_status == DOES_NOT_EXIST)
00131       printf(" - No publisher provided\n");
00132     else
00133       printf(" - Publisher: %s\n", pub_loader.getClassDescription(td.pub_name).c_str());
00134     if (td.sub_status == DOES_NOT_EXIST)
00135       printf(" - No subscriber provided\n");
00136     else
00137       printf(" - Subscriber: %s\n", sub_loader.getClassDescription(td.sub_name).c_str());
00138   }
00139   
00140   return 0;
00141 }


image_transport
Author(s): Patrick Mihelich
autogenerated on Tue Jun 6 2017 02:33:36