test.cpp
Go to the documentation of this file.
00001 #define OROCOS_TARGET gnulinux
00002 #include <rtt/types/TypekitPlugin.hpp>
00003 #include <rtt/typekit/RealTimeTypekit.hpp>
00004 #include "Types.hpp"
00005 #include "Plugin.hpp"
00006 
00007 #ifdef WITH_CORBA
00008 #include <omniORB4/CORBA.h>
00009 #include <rtt/transports/corba/CorbaLib.hpp>
00010 #include <rtt/transports/corba/CorbaTypeTransporter.hpp>
00011 #include "build/.orogen/typekit/transports/corba/opaqueTypesC.h"
00012 #include ".orogen/typekit/transports/corba/TransportPlugin.hpp"
00013 #endif
00014 
00015 #ifdef WITH_TYPELIB
00016 #include "transports/typelib/TransportPlugin.hpp"
00017 #include <rtt/typelib/TypelibMarshallerBase.hpp>
00018 #endif
00019 
00020 #include ".orogen/typekit/OpaqueConvertions.hpp"
00021 
00022 #include <rtt/os/main.h>
00023 #include <rtt/types/Types.hpp>
00024 #include <rtt/PropertyBag.hpp>
00025 #include <rtt/Property.hpp>
00026 #include <rtt/internal/DataSource.hpp>
00027 #include <rtt/types/PropertyDecomposition.hpp>
00028 #include <rtt/marsh/PropertyMarshaller.hpp>
00029 #include <rtt/marsh/PropertyDemarshaller.hpp>
00030 #include <iostream>
00031 #include <fstream>
00032 #include <typeinfo>
00033 #include <stdexcept>
00034 
00035 using namespace RTT;
00036 using namespace RTT::types;
00037 using namespace RTT::internal;
00038 using namespace RTT::marsh;
00039 using namespace orogen_typekits;
00040 using std::cerr;
00041 using std::endl;
00042 
00043 namespace TestOpaque {
00044     inline std::ostream& operator << (std::ostream& io, Position_m const& data) {
00045         io << "{ .timestamp = " << data.timestamp << ", .p.x" << data.p.x << ", .p.y" << data.p.y << "}";
00046         return io;
00047     }
00048 }
00049 namespace std {
00050     extern std::ostream& operator << (std::ostream& io, std::vector<float> const& data);
00051     extern std::ostream& operator << (std::ostream& io, std::vector<int> const& data);
00052 }
00053 template<typename T>
00054 T identity(T const& value) { return value; }
00055 
00056 #ifdef WITH_TYPELIB
00057 template<typename OrocosType, typename TypelibType>
00058 void fromIntermediate(OrocosType& orocos_value, TypelibType& typelib_value)
00059 {
00060     ValueDataSource<OrocosType>* data_source
00061         = new ValueDataSource<OrocosType>();
00062     data_source->ref();
00063 
00064     TypeInfo const* type = data_source->getTypeInfo();
00065     orogen_transports::TypelibMarshallerBase* transport =
00066         dynamic_cast<orogen_transports::TypelibMarshallerBase*>(type->getProtocol(orogen_transports::TYPELIB_MARSHALLER_ID));
00067 
00068     orogen_transports::TypelibMarshallerBase::Handle* handle =
00069         transport->createSample();
00070     transport->setTypelibSample(handle, reinterpret_cast<uint8_t*>(&typelib_value));
00071     transport->writeDataSource(*data_source, handle);
00072     orocos_value = data_source->get();
00073 
00074     transport->deleteHandle(handle);
00075     data_source->deref();
00076 }
00077 
00078 template<typename T, typename Getter>
00079 bool generic_typelib_test(T const& testValue, TypeInfo const& ti, Getter get_test_value)
00080 {
00081     cerr << "- testing Typelib marshalling/unmarshalling ..." << endl;
00082     ConstantDataSource<T>* source
00083         = new ConstantDataSource<T>(testValue);
00084     source->ref();
00085 
00086     orogen_transports::TypelibMarshallerBase* transport =
00087         dynamic_cast<orogen_transports::TypelibMarshallerBase*>(ti.getProtocol(orogen_transports::TYPELIB_MARSHALLER_ID));
00088 
00089     std::vector<uint8_t> buffer;
00090     orogen_transports::TypelibMarshallerBase::Handle* handle =
00091         transport->createSample();
00092     transport->readDataSource(*source, handle);
00093     transport->marshal(buffer, handle);
00094     transport->deleteHandle(handle);
00095     source->deref();
00096 
00097     handle = transport->createSample();
00098     transport->unmarshal(buffer, handle);
00099     ValueDataSource<T> unmarshalled;
00100     transport->writeDataSource(unmarshalled, handle);
00101     transport->deleteHandle(handle);
00102 
00103     if (!(get_test_value(unmarshalled.get()) == get_test_value(testValue)))
00104     {
00105         cerr << "unmarshalled Typelib data does not match original data" << endl;
00106         return false;
00107     }
00108     return true;
00109 }
00110 #endif
00111 
00112 /* This is a generic test of type handling.
00113  * - it marshals the type into a XML file. This file can then be compared
00114  *   with an expected content by the Ruby test case.
00115  * - it does the same with a CPF file
00116  * - it unmarshals the CPF file and checks that both values are equal
00117  * - if the test is done with CORBA, it also converts to/from any and compares
00118  *   the two values.
00119  */
00120 template<typename T, typename Getter>
00121 bool generic_type_handling_test(std::string const& name, T const& testValue, TypeInfo const& ti,
00122         Getter get_test_value)
00123 {
00124     ConstantDataSource<T>* source
00125         = new ConstantDataSource<T>(testValue);
00126     source->ref();
00127 
00128     std::cerr << "disabled XML decomposition/recomposition test" << std::endl;
00129 
00130     //PropertyBag bag;
00131     //ti.decomposeType(source, bag);
00132 
00135     //std::ofstream xml_file((name + ".xml").c_str());
00136     //XMLMarshaller<std::ostream> xml_output(xml_file);
00137     //xml_output.serialize(bag);
00138 
00141     //PropertyMarshaller cpf_output(name + ".cpf");
00142     //cpf_output.serialize(bag);
00143     //cpf_output.flush();
00144 
00145     //PropertyBag input_bag;
00146     //PropertyDemarshaller cpf_input(name + ".cpf");
00147     //cpf_input.deserialize(input_bag);
00148 
00149     //cerr << "Testing PropertyBag composition" << endl;
00150     //{ ValueDataSource<T>* reader = new ValueDataSource<T>();
00151     //    reader->ref();
00152     //    Property<PropertyBag> bag("", "", input_bag);
00153     //    if (!ti.composeType(bag.getDataSource(), reader))
00154     //    {
00155     //        cerr << "cannot recompose type" << endl;
00156     //        return false;
00157     //    }
00158 
00159     //    T value = reader->get();
00160     //    if (!(get_test_value(value) == get_test_value(testValue)))
00161     //    {
00162     //        cerr << "error. Expected\n\n" << get_test_value(testValue) <<
00163     //            "\n\nand got\n\n" << get_test_value(value) << endl;
00164     //    }
00165     //    reader->deref();
00166     //}
00167 
00168 #ifdef WITH_CORBA
00169     std::cerr << "Testing CORBA marshalling/unmarshalling ..." << std::endl;
00170     { RTT::corba::CorbaTypeTransporter* transport =
00171             dynamic_cast<RTT::corba::CorbaTypeTransporter*>(ti.getProtocol(ORO_CORBA_PROTOCOL_ID));
00172 
00173         CORBA::Any* result = transport->createAny(source);
00174 
00175         ValueDataSource<T>* reader = new ValueDataSource<T>();
00176         reader->ref();
00177         transport->updateFromAny(result, reader);
00178 
00179         T value = reader->get();
00180         if (!(get_test_value(value) == get_test_value(testValue)))
00181         {
00182             cerr << "error in CORBA marshalling/demarshalling" << endl;
00183             return false;
00184         }
00185         delete result;
00186         reader->deref();
00187     }
00188 #endif
00189 
00190 #ifdef WITH_TYPELIB
00191     if (!generic_typelib_test(testValue, ti, get_test_value))
00192         return false;
00193 #endif
00194 
00195     source->deref();
00196     return true;
00197 }
00198 
00199 bool test_plain_opaque()
00200 {
00201     cerr << "\n======== Testing plain opaque handling ========" << endl;
00202 
00203     TypeInfoRepository::shared_ptr ti = TypeInfoRepository::Instance();
00204     TypeInfo* type = ti->type("/NotOrogenCompatible/Point2D");
00205     if (! type)
00206     {
00207         cerr << "cannot find /NotOrogenCompatible/Point2D in the type info repository" << endl;
00208         return false;
00209     }
00210 
00211     std::cerr << "Testing the initialization of the types from an intermediate..." << std::endl;
00212     {
00213         TestOpaque::Point2D testValue = { 100, 20, 30 };
00214         NotOrogenCompatible::Point2D p(0, 0);
00215         fromIntermediate(p, testValue);
00216 
00217         if (testValue.x != p.x() || testValue.y != p.y())
00218         {
00219             cerr << "error in Typelib marshalling" << endl;
00220             return false;
00221         }
00222     }
00223 
00224 
00225     NotOrogenCompatible::Point2D testValue(10, 20);
00226     if (!generic_type_handling_test("opaque", testValue, *type, &::identity<NotOrogenCompatible::Point2D> ))
00227         return false;
00228 
00229     return true;
00230 }
00231 
00232 bool test_composed_opaque()
00233 {
00234     cerr << "\n======== Testing opaque field in struct ========" << endl;
00235 
00236     TypeInfoRepository::shared_ptr ti = TypeInfoRepository::Instance();
00237     TypeInfo* type = ti->type("/TestOpaque/Position");
00238     if (! type)
00239     {
00240         cerr << "cannot find /TestOpaque/Position in the type info repository" << endl;
00241         return 1;
00242     }
00243 
00244     TestOpaque::Position testValue;
00245     testValue.timestamp = 10;
00246     testValue.p.x() = 20;
00247     testValue.p.y() = 30;
00248 
00249     generic_type_handling_test("composed_opaque", testValue, *type, &::identity<TestOpaque::Position> );
00250 
00251     std::cerr << "Testing the initialization of the types from an intermediate..." << std::endl;
00252     {
00253         TestOpaque::Position_m testValue = { 100, { 20, 30 } };
00254         TestOpaque::Position p;
00255         memset(&p, 0, sizeof(p));
00256         fromIntermediate(p, testValue);
00257 
00258         if (testValue.timestamp != p.timestamp || testValue.p.x != p.p.x() || testValue.p.y != p.p.y())
00259         {
00260             cerr << "error in Typelib marshalling" << endl;
00261             return false;
00262         }
00263     }
00264 
00265     return true;
00266 }
00267 
00268 template<typename T>
00269 T get_ptr_content(boost::shared_ptr<T> const& left)
00270 { return *left; }
00271 
00272 template<typename T>
00273 T get_ro_ptr_content(RTT::extras::ReadOnlyPointer<T> const& left)
00274 { return *left; }
00275 
00276 bool test_shared_pointer()
00277 {
00278     cerr << "\n======== Testing shared pointer ========" << endl;
00279 
00280     TypeInfoRepository::shared_ptr ti = TypeInfoRepository::Instance();
00281     TypeInfo* type = ti->type("/boost/shared_ptr</std/vector</float>>");
00282     if (! type)
00283     {
00284         cerr << "cannot find /boost/shared_ptr</std/vector</float>> in the type info repository" << endl;
00285         return false;
00286     }
00287 
00288     boost::shared_ptr< std::vector<float> > testValue( new std::vector<float> );
00289     std::vector<float>& data = *testValue;
00290 
00291     for (int i = 0; i < 10; ++i)
00292         data.push_back(i);
00293 
00294     generic_type_handling_test("shared_ptr__opaque_type", testValue, *type, &get_ptr_content< std::vector<float> >);
00295 
00296     std::cerr << "Testing the initialization of the types from an intermediate..." << std::endl;
00297     {
00298         boost::shared_ptr< std::vector<float> > result;
00299         fromIntermediate(result, *testValue);
00300 
00301         for (int i = 0; i < data.size(); ++i)
00302             if ((*result)[i] != (*testValue)[i])
00303             {
00304                 cerr << "error in type initialization from an intermediate" << endl;
00305                 return false;
00306             }
00307     }
00308 
00309     return true;
00310 }
00311 
00312 bool test_shared_ptr_shortcut()
00313 {
00314     cerr << "\n======== Testing shared pointer (from #shared_ptr) ========" << endl;
00315 
00316     TypeInfoRepository::shared_ptr ti = TypeInfoRepository::Instance();
00317     TypeInfo* type = ti->type("/boost/shared_ptr</std/vector</int32_t>>");
00318     if (! type)
00319     {
00320         cerr << "cannot find /boost/shared_ptr</std/vector</int32_t>> in the type info repository" << endl;
00321         return false;
00322     }
00323 
00324     boost::shared_ptr< std::vector<int> > testValue( new std::vector<int> );
00325     std::vector<int>& data = *testValue;
00326 
00327     for (int i = 0; i < 10; ++i)
00328         data.push_back(i);
00329 
00330 
00331     generic_type_handling_test("shared_ptr__shared_ptr", testValue, *type, &get_ptr_content< std::vector<int> >);
00332 
00333     std::cerr << "Testing the initialization of the types from an intermediate..." << std::endl;
00334     {
00335         boost::shared_ptr< std::vector<int> > result;
00336         fromIntermediate(result, data);
00337 
00338         for (int i = 0; i < data.size(); ++i)
00339             if ((*result)[i] != (*testValue)[i])
00340             {
00341                 cerr << "error in type initialization from an intermediate" << endl;
00342                 return false;
00343             }
00344     }
00345 
00346     return true;
00347 }
00348 
00349 bool test_ro_ptr()
00350 {
00351     cerr << "\n======== Testing ReadOnlyPointer (from #ro_ptr) ========" << endl;
00352 
00353     TypeInfoRepository::shared_ptr ti = TypeInfoRepository::Instance();
00354     TypeInfo* type = ti->type("/RTT/extras/ReadOnlyPointer</std/vector</int32_t>>");
00355     if (! type)
00356     {
00357         cerr << "cannot find /RTT/extras/ReadOnlyPointer</std/vector</int32_t>> in the type info repository" << endl;
00358         return false;
00359     }
00360 
00361     std::vector<int>* data = new std::vector<int>();
00362     for (int i = 0; i < 10; ++i)
00363         data->push_back(i);
00364 
00365     RTT::extras::ReadOnlyPointer< std::vector<int> > testValue(data);
00366 
00367 
00368     generic_type_handling_test("readonlypointer", testValue, *type, &get_ro_ptr_content< std::vector<int> >);
00369 
00370     std::cerr << "Testing the initialization of the types from an intermediate..." << std::endl;
00371     {
00372         RTT::extras::ReadOnlyPointer< std::vector<int> > result;
00373         fromIntermediate(result, *data);
00374 
00375         for (int i = 0; i < data->size(); ++i)
00376             if ((*result)[i] != (*testValue)[i])
00377             {
00378                 cerr << "error in type initialization from an intermediate" << endl;
00379                 return false;
00380             }
00381     }
00382 
00383     return true;
00384 }
00385 
00386 
00387 int ORO_main(int argc, char** argv)
00388 {
00389     log().setLogLevel( Logger::Debug );
00390     RTT::types::TypekitRepository::Import( new RTT::types::RealTimeTypekitPlugin );
00391     RTT::types::TypekitRepository::Import( new orogen_typekits::opaqueTypekitPlugin );
00392 #ifdef WITH_CORBA
00393     RTT::types::TypekitRepository::Import( new orogen_typekits::opaqueCorbaTransportPlugin );
00394 #endif
00395 #ifdef WITH_TYPELIB
00396     RTT::types::TypekitRepository::Import( new orogen_typekits::opaqueTypelibTransportPlugin );
00397 #endif
00398 
00399     if (!test_plain_opaque())
00400     {
00401         cerr << "plain_opaque failed" << endl;
00402         return 1;
00403     }
00404     if (!test_composed_opaque())
00405     {
00406         cerr << "composed_opaque failed" << endl;
00407         return 1;
00408     }
00409     if (!test_shared_pointer())
00410     {
00411         cerr << "shared_ptr failed" << endl;
00412         return 1;
00413     }
00414     if (!test_shared_ptr_shortcut())
00415     {
00416         cerr << "shared_ptr (from #shared_ptr) failed" << endl;
00417         return 1;
00418     }
00419     if (!test_ro_ptr())
00420     {
00421         cerr << "ReadOnlyPointer failed" << endl;
00422         return 1;
00423     }
00424 
00425     return 0;
00426 }
00427 


orogen
Author(s): Sylvain Joyeux/sylvain.joyeux@m4x.org
autogenerated on Thu Jan 2 2014 11:38:57