object.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, 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 #ifndef ROSMATLAB_OBJECT_H
00030 #define ROSMATLAB_OBJECT_H
00031 
00032 #include <rosmatlab/exception.h>
00033 #include <rosmatlab/options.h>
00034 
00035 #include <boost/shared_ptr.hpp>
00036 #include <boost/function.hpp>
00037 #include <boost/type_traits.hpp>
00038 
00039 #include "mex.h"
00040 
00041 #include <stdint.h>
00042 
00043 namespace rosmatlab {
00044 
00045 namespace {
00046   struct null_deleter {
00047     void operator()(void const *) const {}
00048   };
00049 }
00050 
00051 template <class Type>
00052 class Object
00053 {
00054 public:
00055   typedef boost::shared_ptr<Type> Ptr;
00056 
00057   Object() { construct(); }
00058   Object(Type *instance) { *this = instance; construct(); }
00059   Object(const Ptr &instance) { *this = instance; construct(); }
00060   Object(const Object &other) { *this = other; construct(); }
00061   virtual ~Object() { if (handle_) mxDestroyArray(handle_); }
00062 
00063   const Ptr &instance() const { return instance_; }
00064   mxArray *handle() const { return handle_; }
00065 
00066   Type* get() { return instance_.get(); }
00067   const Type* get() const { return instance_.get(); }
00068   Type &operator*() { return *instance_; }
00069   const Type &operator*() const { return *instance_; }
00070 
00071   Object<Type> &operator=(const Object &other) {
00072     return *this = other.instance_;
00073   }
00074 
00075   Object<Type> &operator=(Type *instance) {
00076     return *this = Ptr(instance, null_deleter());
00077   }
00078 
00079   Object<Type> &operator=(const Ptr &instance) {
00080     instance_ = instance;
00081     return *this;
00082   }
00083 
00084   static Object<Type> *byHandle(const mxArray *handle) {
00085     const mxArray *ptr = 0;
00086     if (!handle) return 0;
00087     // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Searching for object of type %s (%s)...\n", getClassName(), typeid(Type).name());
00088     if (mxIsClass(handle, class_name_)) {
00089       // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Handle is a %s class\n", mxGetClassName(handle));
00090       ptr = mxGetProperty(handle, 0, "handle");
00091     } else if (mxIsStruct(handle)) {
00092       // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Handle is a struct\n");
00093       ptr = mxGetField(handle, 0, "handle");
00094     } else if (mxIsDouble(handle)) {
00095       // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Handle is a double\n");
00096       ptr = handle;
00097     }
00098     if (!ptr || !mxIsDouble(ptr) || !(mxGetNumberOfElements(ptr) > 0) || !mxGetPr(ptr)) throw Exception("invalid handle");
00099 
00100     Object<Type> *object = reinterpret_cast<Object<Type> *>(static_cast<uint64_t>(*mxGetPr(ptr)));
00101     return object;
00102   }
00103 
00104   static const char *getClassName() { return class_name_; }
00105 
00106 private:
00107   boost::shared_ptr<Type> instance_;
00108   mxArray *handle_;
00109   static const char *class_name_;
00110 
00111   void construct() {
00112     handle_ = mxCreateDoubleScalar(reinterpret_cast<uint64_t>(this));
00113     mexMakeArrayPersistent(handle_);
00114     assert(byHandle(handle()) == this);
00115   }
00116 };
00117 
00118 template <class Type>
00119 Type *getObject(const mxArray *handle) {
00120   Object<Type> *object = Object<Type>::byHandle(handle);
00121   if (!object) return 0;
00122   return object->get();
00123 }
00124 
00125 namespace internal {
00126 
00127   template <typename T> static inline mxArray *mx_cast(T result) {
00128     return mxCreateDoubleScalar(result);
00129   }
00130 
00131   template<> mxArray *mx_cast(mxArray *result) {
00132     return result;
00133   }
00134 
00135   template<> mxArray *mx_cast(bool result) {
00136     return mxCreateLogicalScalar(result);
00137   }
00138 
00139   template<> mxArray *mx_cast(const std::string& result) {
00140     return mxCreateString(result.c_str());
00141   }
00142 
00143   template <class Type, class Result>
00144   static inline void callMex(const boost::function<Result(Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00145   {
00146     plhs[0] = mx_cast(func(obj, nlhs, plhs, nrhs, prhs));
00147   }
00148 
00149   template <class Type, class Result>
00150   static inline void callMex(const boost::function<Result(Type *, int nrhs, const mxArray *prhs[])> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00151   {
00152     plhs[0] = mx_cast(func(obj, nrhs, prhs));
00153   }
00154 
00155   template <class Type, class Result>
00156   static inline void callMex(const boost::function<Result(Type *)> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00157   {
00158     plhs[0] = mx_cast(func(obj));
00159   }
00160 
00161   template <class Type>
00162   static inline void callMex(const boost::function<void(Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00163   {
00164     func(obj, nlhs, plhs, nrhs, prhs);
00165   }
00166 
00167   template <class Type>
00168   static inline void callMex(const boost::function<void(Type *, int nrhs, const mxArray *prhs[])> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00169   {
00170     func(obj, nrhs, prhs);
00171   }
00172 
00173   template <class Type>
00174   static inline void callMex(const boost::function<void(Type *)> &func, Type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
00175   {
00176     func(obj);
00177   }
00178 
00179   template <class Signature>
00180   class MexFunctor {
00181   public:
00182     typedef Signature* function_pointer;
00183     typedef boost::function<Signature> function_type;
00184     typedef typename boost::remove_pointer<typename boost::function_traits<Signature>::arg1_type>::type object_type;
00185 
00186     MexFunctor(const function_type& func) : target_(func) {}
00187     MexFunctor(function_pointer func) : target_(func) {}
00188 
00189     void operator()(object_type *obj, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) {
00190       callMex(target_, obj, nlhs, plhs, nrhs, prhs);
00191     }
00192 
00193   private:
00194     boost::function<Signature> target_;
00195   };
00196 }
00197 
00198 template <class Type>
00199 class MexMethodMap {
00200 private:
00201 //  typedef boost::function<void(Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])> FunctionType1;
00202 //  typedef boost::function<void(Type *, int nrhs, const mxArray *prhs[])> FunctionType2;
00203 //  typedef boost::function<void(Type *)> FunctionType3;
00204 //  typedef boost::function<mxArray *(Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])> FunctionType4;
00205 //  typedef boost::function<mxArray *(Type *, int nrhs, const mxArray *prhs[])> FunctionType5;
00206 //  typedef boost::function<mxArray *(Type *)> FunctionType6;
00207 
00208 //  std::map<std::string,FunctionType1> methods1_;
00209 //  std::map<std::string,FunctionType2> methods2_;
00210 //  std::map<std::string,FunctionType3> methods3_;
00211 //  std::map<std::string,FunctionType4> methods4_;
00212 //  std::map<std::string,FunctionType5> methods5_;
00213 //  std::map<std::string,FunctionType6> methods6_;
00214 
00215   std::map<std::string,boost::function<void(Type *, int, mxArray *[], int, const mxArray *[])> > methods_;
00216 
00217   bool initialized_;
00218   bool throw_on_unknown_;
00219 
00220 public:
00221   MexMethodMap() : initialized_(false), throw_on_unknown_(false) {}
00222 
00223   bool initialize() {
00224     if (!initialized_) {
00225       initialized_ = true;
00226       return false;
00227     }
00228     return true;
00229   }
00230 
00231   operator void *() const {
00232     return initialized_;
00233   }
00234 
00235   MexMethodMap &throwOnUnknown(bool value = true) {
00236     throw_on_unknown_ = value;
00237     return *this;
00238   }
00239 
00240   template <typename Result>
00241   MexMethodMap &add(const std::string& name, Result (Type::*function)(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])) {
00242     methods_[name] = internal::MexFunctor<Result (Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])>(function);
00243     return *this;
00244   }
00245 
00246   template <typename Result>
00247   MexMethodMap &add(const std::string& name, Result (Type::*function)(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) const) {
00248     methods_[name] = internal::MexFunctor<Result (const Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])>(function);
00249     return *this;
00250   }
00251 
00252   template <typename Result>
00253   MexMethodMap &add(const std::string& name, Result (Type::*function)(int nrhs, const mxArray *prhs[])) {
00254     methods_[name] = internal::MexFunctor<Result (Type *, int nrhs, const mxArray *prhs[])>(function);
00255     return *this;
00256   }
00257 
00258   template <typename Result>
00259   MexMethodMap &add(const std::string& name, Result (Type::*function)(int nrhs, const mxArray *prhs[]) const) {
00260     methods_[name] = internal::MexFunctor<Result (const Type *, int nrhs, const mxArray *prhs[])>(function);
00261     return *this;
00262   }
00263 
00264   template <typename Result>
00265   MexMethodMap &add(const std::string& name, Result (Type::*function)()) {
00266     methods_[name] = internal::MexFunctor<Result (Type *)>(function);
00267     return *this;
00268   }
00269 
00270   template <typename Result>
00271   MexMethodMap &add(const std::string& name, Result (Type::*function)() const) {
00272     methods_[name] = internal::MexFunctor<Result (const Type *)>(function);
00273     return *this;
00274   }
00275 
00276 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])) {
00277 //    methods_[name] = internal::MexFunctor<mxArray *(Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])>(function);
00278 //    return *this;
00279 //  }
00280 
00281 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) const) {
00282 //    methods_[name] = internal::MexFunctor<mxArray *(const Type *, int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])>(function);
00283 //    return *this;
00284 //  }
00285 
00286 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)(int nrhs, const mxArray *prhs[])) {
00287 //    methods_[name] = internal::MexFunctor<mxArray *(Type *, int nrhs, const mxArray *prhs[])>(function);
00288 //    return *this;
00289 //  }
00290 
00291 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)(int nrhs, const mxArray *prhs[]) const) {
00292 //    methods_[name] = internal::MexFunctor<mxArray *(const Type *, int nrhs, const mxArray *prhs[])>(function);
00293 //    return *this;
00294 //  }
00295 
00296 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)()) {
00297 //    methods_[name] = internal::MexFunctor<mxArray *(Type *)>(function);
00298 //    return *this;
00299 //  }
00300 
00301 //  MexMethodMap &add(const std::string& name, mxArray *(Type::*function)() const) {
00302 //    methods_[name] = internal::MexFunctor<mxArray *(const Type *)>(function);
00303 //    return *this;
00304 //  }
00305 
00306   bool has(const std::string& name) const {
00307     return methods_.count(name);
00308   }
00309 
00310   bool call(Type *object, const std::string& name, int &nlhs, mxArray **&plhs, int &nrhs, const mxArray **&prhs) const {
00311     if (methods_.count(name)) {
00312       methods_.at(name)(object, nlhs, plhs, nrhs, prhs);
00313       return true;
00314     }
00315 
00316     if (throw_on_unknown_)
00317       throw Exception(std::string() + "unknown method '" + name + "' for objects of class " + Object<Type>::getClassName());
00318 
00319     if (has("default")) {
00320       return call(object, "default", nlhs, plhs, nrhs, prhs);
00321     }
00322 
00323     return false;
00324   }
00325 };
00326 
00327 template <class Type>
00328 Type *mexClassHelper(int &nlhs, mxArray **&plhs, int &nrhs, const mxArray **&prhs, std::string& method, const MexMethodMap<Type>& methods = MexMethodMap<Type>()) {
00329   if (nrhs < 1) {
00330     throw ArgumentException(1);
00331   }
00332 
00333   Type *object = getObject<Type>(*prhs++); nrhs--;
00334   method.clear();
00335   if (nrhs) { method = Options::getString(*prhs++); nrhs--; }
00336 
00337   // construction
00338   if (method == "create") {
00339     delete object;
00340     // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Creating new %s object\n", Object<Type>::getClassName().c_str());
00341     object = new Type(nrhs, prhs);
00342     plhs[0] = object->handle();
00343     method.clear();
00344     return object;
00345   }
00346 
00347   // destruction
00348   if (method == "delete") {
00349     // mexPrintf(ROSMATLAB_PRINTF_PREFIX "Deleting %s object\n", Object<Type>::getClassName().c_str());
00350     delete object;
00351     return 0;
00352   }
00353 
00354   // for all other methods the object must exist
00355   if (!object) {
00356     throw Exception("Instance not found");
00357   }
00358 
00359   // execute method
00360   if (methods.call(object, method, nlhs, plhs, nrhs, prhs)) {
00361     method.clear();
00362   }
00363 
00364   return object;
00365 }
00366 
00367 template <class Type>
00368 Type *mexClassHelper(int &nlhs, mxArray **&plhs, int &nrhs, const mxArray **&prhs, const MexMethodMap<Type>& methods = MexMethodMap<Type>()) {
00369   std::string method;
00370   return mexClassHelper(nlhs, plhs, nrhs, prhs, method, methods);
00371 }
00372 
00373 } // namespace rosmatlab
00374 
00375 #endif // ROSMATLAB_OBJECT_H


rosmatlab
Author(s): Johannes Meyer
autogenerated on Fri Jul 25 2014 06:48:12