introspection.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #include <introspection/field.h>
00030 #include <introspection/type.h>
00031 #include <introspection/introspection.h>
00032 #include <introspection/message_expansion.h>
00033 
00034 #include <dlfcn.h>
00035 #include <boost/filesystem.hpp>
00036 
00037 namespace cpp_introspection {
00038 
00039   static M_Package g_packages;
00040   static V_Package g_repository;
00041   static M_Message g_messages_by_name;
00042   static M_Message g_messages_by_md5sum;
00043   static M_TypeInfo_Message g_messages_by_typeid;
00044   static V_string g_loaded_libraries;
00045 
00046   PackagePtr package(const std::string& pkg)
00047   {
00048     if (!g_packages.count(pkg)) return PackagePtr();
00049     return g_packages[pkg].lock();
00050   }
00051 
00052   const V_Package &packages() {
00053     return g_repository;
00054   }
00055 
00056   MessagePtr messageByDataType(const std::string& data_type, const std::string& package)
00057   {
00058     if (!package.empty()) return messageByDataType(package + "/" + data_type);
00059     if (data_type == "Header") return g_messages_by_name[ros::message_traits::datatype<std_msgs::Header>()].lock();
00060     if (!g_messages_by_name.count(data_type)) return MessagePtr();
00061     return g_messages_by_name[data_type].lock();
00062   }
00063 
00064   MessagePtr messageByMD5Sum(const std::string& md5sum)
00065   {
00066     if (!g_messages_by_md5sum.count(md5sum)) return MessagePtr();
00067     return g_messages_by_md5sum[md5sum].lock();
00068   }
00069 
00070   MessagePtr messageByTypeId(const std::type_info &type_info) {
00071     if (!g_messages_by_typeid.count(&type_info)) return MessagePtr();
00072     return g_messages_by_typeid[&type_info].lock();
00073   }
00074 
00075   PackagePtr Package::add(const PackagePtr& package)
00076   {
00077     if (g_packages.count(package->getName())) return g_packages[package->getName()].lock();
00078     g_repository.push_back(package);
00079     g_packages[package->getName()] = package;
00080     return package;
00081   }
00082 
00083   std::vector<std::string> Package::getMessages() const
00084   {
00085     std::vector<std::string> messages;
00086     for(std::vector<MessagePtr>::const_iterator it = messages_.begin(); it != messages_.end(); ++it)
00087       messages.push_back((*it)->getName());
00088 
00089     return messages;
00090   }
00091 
00092   MessagePtr Package::message(const std::string& message) const
00093   {
00094     return messageByDataType(std::string(getName()) + "/" + message);
00095   }
00096 
00097   MessagePtr Package::add(const MessagePtr& message)
00098   {
00099     if (g_messages_by_name.count(message->getDataType())) return g_messages_by_name[message->getDataType()].lock();
00100     messages_.push_back(message);
00101     g_messages_by_name[message->getDataType()] = message;
00102     g_messages_by_md5sum[message->getMD5Sum()] = message;
00103     g_messages_by_typeid[&(message->getTypeId())] = message;
00104     return message;
00105   }
00106 
00107   MessagePtr expand(const MessagePtr& message, const std::string &separator, const std::string &prefix)
00108   {
00109     return MessagePtr(new ExpandedMessage(message, separator, prefix));
00110   }
00111 
00112   void ExpandedMessage::expand(const MessagePtr &message, const std::string& prefix) {
00113     for(Message::const_iterator i = message->begin(); i != message->end(); i++) {
00114       FieldPtr field = *i;
00115 
00116       for(std::size_t j = 0; j < field->size(); j++) {
00117         std::string field_name = (!prefix.empty() ? prefix + separator_ : "") + field->getName();
00118         if (field->isContainer()) field_name += boost::lexical_cast<std::string>(j);
00119 
00120         if (field->isMessage()) {
00121           MessagePtr expanded(field->expand(j));
00122           if (!expanded) {
00123             ROS_WARN("Expansion of %s failed: Could not expand field %s with unknown type %s", getDataType(), field->getName(), field->getDataType());
00124             continue;
00125           }
00126           expand(expanded, field_name);
00127         } else {
00128           FieldPtr expanded(new ExpandedField(*field, field_name, j));
00129           fields_.push_back(expanded);
00130           fields_by_name_[field_name] = expanded;
00131           field_names_.push_back(expanded->getName());
00132         }
00133       }
00134     }
00135   }
00136 
00137   V_string Message::getFields(bool expand, const std::string& separator, const std::string& prefix) const
00138   {
00139     V_string fields;
00140     return getFields(fields, expand, separator, prefix);
00141   }
00142 
00143   V_string& Message::getFields(V_string& fields, bool expand, const std::string& separator, const std::string& prefix) const
00144   {
00145     for(const_iterator it = begin(); it != end(); ++it) {
00146       FieldPtr field = *it;
00147       std::string base(prefix + field->getName());
00148 
00149       for (std::size_t index = 0; index < field->size(); ++index) {
00150         std::string name(base);
00151         if (field->isArray()) name = name + boost::lexical_cast<std::string>(index);
00152 
00153         if (expand && field->isMessage()) {
00154           MessagePtr expanded = field->expand(index);
00155           if (!expanded) {
00156             ROS_WARN("Expansion of %s failed: Could not expand field %s with unknown type %s", getDataType(), field->getName(), field->getDataType());
00157             continue;
00158           }
00159           expanded->getFields(fields, expand, separator, name + separator);
00160 
00161         } else {
00162           fields.push_back(name);
00163         }
00164       }
00165     }
00166 
00167     return fields;
00168   }
00169 
00170   V_string Message::getTypes(bool expand) const
00171   {
00172     V_string types;
00173     return getTypes(types, expand);
00174   }
00175 
00176   V_string& Message::getTypes(V_string& types, bool expand) const
00177   {
00178     for(const_iterator it = begin(); it != end(); ++it) {
00179       FieldPtr field = *it;
00180 
00181       for (std::size_t index = 0; index < field->size(); ++index) {
00182         if (expand && field->isMessage()) {
00183           MessagePtr expanded = field->expand(index);
00184           if (!expanded) {
00185             ROS_WARN("Expansion of %s failed: Could not expand field %s with unknown type %s", getDataType(), field->getName(), field->getDataType());
00186             continue;
00187           }
00188           expanded->getTypes(types, expand);
00189 
00190         } else {
00191           types.push_back(field->isArray() ? field->getValueType() : field->getDataType());
00192         }
00193       }
00194     }
00195 
00196     return types;
00197   }
00198 
00199   std::vector<boost::any> Message::getValues(bool expand) const
00200   {
00201     std::vector<boost::any> values;
00202     return getValues(values, expand);
00203   }
00204 
00205   std::vector<boost::any>& Message::getValues(std::vector<boost::any>& values, bool expand) const
00206   {
00207     if (!hasInstance()) return values;
00208 
00209     for(const_iterator it = begin(); it != end(); ++it) {
00210       FieldPtr field = *it;
00211 
00212       for (std::size_t index = 0; index < field->size(); ++index) {
00213         if (expand && field->isMessage()) {
00214           MessagePtr expanded = field->expand(index);
00215           if (!expanded) {
00216             ROS_WARN("Expansion of %s failed: Could not expand field %s with unknown type %s", getDataType(), field->getName(), field->getDataType());
00217             continue;
00218           }
00219           expanded->getValues(values, expand);
00220 
00221         } else {
00222           values.push_back(field->get(index));
00223         }
00224       }
00225     }
00226 
00227     return values;
00228   }
00229 
00230   MessagePtr Field::expand(std::size_t i) const {
00231     if (!isMessage()) return MessagePtr();
00232     return messageByTypeId(this->getTypeId());
00233   }
00234 
00235   using namespace boost::filesystem;
00236   void load(const std::string& library_or_path)
00237   {
00238     path path(library_or_path);
00239     if (is_directory(path)) {
00240       ROS_DEBUG_STREAM_NAMED(ROS_PACKAGE_NAME, "Searching directory " << path << "...");
00241       for(directory_iterator entry(path); entry != directory_iterator(); ++entry) {
00242         ROS_DEBUG_STREAM_NAMED(ROS_PACKAGE_NAME, "  " << *entry << "...");
00243         if (is_regular_file(entry->path())) load(entry->path().string());
00244       }
00245 
00246       return;
00247     }
00248 
00249     if (is_regular_file(path)) {
00250       if (path.extension() != ".so") return;
00251       ROS_DEBUG_STREAM_NAMED(ROS_PACKAGE_NAME, "Loading " << path << "...");
00252 
00253       if (std::find(g_loaded_libraries.begin(), g_loaded_libraries.end(), path.string()) != g_loaded_libraries.end()) {
00254         ROS_WARN_STREAM_NAMED(ROS_PACKAGE_NAME, "library " << path << " already loaded");
00255         return;
00256       }
00257 
00258       void *library = dlopen(path.string().c_str(), RTLD_NOW | RTLD_GLOBAL);
00259       const char *error = dlerror();
00260       if (error || !library) {
00261         ROS_ERROR("%s", error);
00262         return;
00263       }
00264 
00265       typedef PackagePtr (*LoadFunction)();
00266       LoadFunction load_fcn = (LoadFunction) dlsym(library, "cpp_introspection_load_package");
00267       error = dlerror();
00268       if (error || !load_fcn) {
00269         ROS_WARN_NAMED(ROS_PACKAGE_NAME, "%s", error);
00270         dlclose(library);
00271         return;
00272       }
00273       PackagePtr package __attribute__((unused)) = (*load_fcn)();
00274 
00275       ROS_INFO_STREAM_NAMED(ROS_PACKAGE_NAME, "Successfully loaded cpp_introspection library " << path);
00276       g_loaded_libraries.push_back(path.string());
00277 
00278 //      for(Package::const_iterator it = package->begin(); it != package->end(); ++it) {
00279 //        ROS_INFO_STREAM_NAMED(ROS_PACKAGE_NAME, "Package " << package->getName() << " contains message " << (*it)->getName() << ":");
00280 //        V_string types = (*it)->getTypes();
00281 //        V_string names = (*it)->getFields();
00282 //        for(V_string::const_iterator it_type = types.begin(), it_name = names.begin(); it_type != types.end() && it_name != names.end(); ++it_type, ++it_name) {
00283 //          ROS_INFO("  %s %s", it_type->c_str(), it_name->c_str());
00284 //        }
00285 //      }
00286     }
00287   }
00288 
00289 } // namespace cpp_introspection
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cpp_introspection
Author(s): Johannes Meyer
autogenerated on Tue Jan 8 2013 17:30:47