GenericObjectContainer.cpp
Go to the documentation of this file.
00001 
00002 #include "vrep_ros_plugin/access.h"
00003 #include "v_repLib.h"
00004 
00005 #include <vrep_ros_plugin/GenericObjectContainer.h>
00006 
00007 #include "vrep_ros_plugin/ConsoleHandler.h"
00008 
00009 
00010 GenericObjectContainer::GenericObjectContainer():
00011         _object_handler_loader("vrep_ros_plugin", "GenericObjectHandler"){
00012 
00013     std::vector< std::string > plugins = _object_handler_loader.getDeclaredClasses();
00014 
00015     std::stringstream ss;
00016     ss << "Available ObjectHandlers: " << std::endl;
00017     for (uint i=0; i<plugins.size();++i){
00018         ss << plugins[i] << std::endl;
00019         try{
00020             _allExistingPlugins.insert ( std::pair<std::string, boost::shared_ptr<GenericObjectHandler> >(plugins[i],_object_handler_loader.createInstance(plugins[i])) );
00021         } catch(pluginlib::PluginlibException& ex){
00022           //handle the class failing to load
00023           ROS_ERROR("The plugin %s failed to load for some reason. Error: %s", plugins[i].c_str(), ex.what());
00024         }
00025     }
00026 
00027     ConsoleHandler::printInConsole(ss);
00028 }
00029 
00030 GenericObjectContainer::~GenericObjectContainer(){
00031         removeAll();
00032 }
00033 
00034 void GenericObjectContainer::removeAll(){
00035         _allObjects.clear();
00036         _allExistingPlugins.clear();
00037 }
00038 
00039 void GenericObjectContainer::removeFromID(int theID){
00040         for (int i=0;i<getCount();i++)
00041         {
00042                 if (_allObjects[i]->getID()==theID)
00043                 {
00044                         _allObjects.erase(_allObjects.begin()+i);
00045                         break;
00046                 }
00047         }
00048 }
00049 
00050 int GenericObjectContainer::insert(boost::shared_ptr<GenericObjectHandler> objectHandler){
00051         int newID=0;
00052         while (getFromID(newID)!=NULL)
00053                 newID++;
00054         _allObjects.push_back(objectHandler);
00055         objectHandler->setID(newID);
00056         return(newID);
00057 }
00058 
00059 boost::shared_ptr<GenericObjectHandler> GenericObjectContainer::getFromID(int theID){
00060         for (int i=0;i<getCount();i++)
00061         {
00062                 if (_allObjects[i]->getID()==theID)
00063                         return(_allObjects[i]);
00064         }
00065         return boost::shared_ptr<GenericObjectHandler>();
00066 }
00067 
00068 boost::shared_ptr<GenericObjectHandler> GenericObjectContainer::getFromIndex(int ind){
00069         if ( (ind<0)||(ind>=getCount()) )
00070                 return boost::shared_ptr<GenericObjectHandler>();
00071         return(_allObjects[ind]);
00072 }
00073 
00074 boost::shared_ptr<GenericObjectHandler> GenericObjectContainer::getFromAssociatedObject(int theAssociatedObjectID){
00075         for (int i=0;i<getCount();i++)
00076         {
00077                 if (_allObjects[i]->getAssociatedObject()==theAssociatedObjectID)
00078                         return(_allObjects[i]);
00079         }
00080         return boost::shared_ptr<GenericObjectHandler>();
00081 }
00082 
00083 int GenericObjectContainer::getCount(){
00084         return(int(_allObjects.size()));
00085 }
00086 
00087 void GenericObjectContainer::startOfSimulation(){ // Relay the message to all GenericObjectHandler objects:
00088         for (int i=0;i<getCount();i++)
00089                 _allObjects[i]->startOfSimulation();
00090 }
00091 
00092 void GenericObjectContainer::endOfSimulation(){ // Relay the message to all GenericObjectHandler objects:
00093         for (int i=0;i<getCount();i++)
00094         {
00095                 if (_allObjects[i]->endOfSimulation())
00096                 { // Means that this object wants to be destroyed
00097                         _allObjects.erase(_allObjects.begin()+i);
00098                         i--;
00099                 }
00100         }
00101 }
00102 
00103 void GenericObjectContainer::handleSimulation(){
00104     // Relay the message to all GenericObjectHandler objects:
00105         for (int i=0;i<getCount();i++)
00106                 _allObjects[i]->handleSimulation();
00107 }
00108 
00109 void GenericObjectContainer::actualizeForSceneContent(){
00110         // 1. We first check which GenericObjectHandler is not valid anymore, and remove it
00111         int i=0;
00112         while (i<int(_allObjects.size()))
00113         {
00114             boost::shared_ptr<GenericObjectHandler> objectHandler=_allObjects[i];
00115                 int associatedObject=objectHandler->getAssociatedObject();
00116                 int uniqueID;
00117                 if (simGetObjectUniqueIdentifier(associatedObject,&uniqueID)==-1)
00118                 { // the object doesn't exist anymore!
00119                         removeFromID(objectHandler->getID());
00120                         i=-1; // ordering in _allObjects might have changed, we start from the beginning
00121                 }
00122                 else
00123                 { // An object with that handle exists, is its unique ID same as getAssociatedObjectUniqueId()?
00124                         if (uniqueID!=objectHandler->getAssociatedObjectUniqueId())
00125                         { // the object doesn't exist anymore! (the object was destroyed and then another object was assigned the same handle (e.g. new scene was loaded))
00126                                 removeFromID(objectHandler->getID());
00127                                 i=-1; // ordering in _allObjects might have changed, we start from the beginning
00128                         } else  {
00129                             // the object still exists. Does it still have its QUADROTOR_DATA_MAIN tag?
00130                                 // a. Get all the developer data attached to this object (this is custom data added by the developer):
00131                                 int buffSize=simGetObjectCustomDataLength(associatedObject,CustomDataHeaders::DEVELOPER_DATA_HEADER);
00132                                 char* datBuff=new char[buffSize];
00133                                 simGetObjectCustomData(associatedObject,CustomDataHeaders::DEVELOPER_DATA_HEADER,datBuff);
00134                                 std::vector<unsigned char> developerCustomData(datBuff,datBuff+buffSize);
00135                                 delete[] datBuff;
00136                                 // b. From that retrieved data, try to extract sub-data with the QUADROTOR_DATA_MAIN tag:
00137                                 std::vector<unsigned char> tempMainData;
00138                                 if (!CAccess::extractSerializationData(developerCustomData,objectHandler->getObjectType(),tempMainData)) // the tag is composed by a string and an integer
00139                                 { // No, there is no data with the QUADROTOR_DATA_MAIN tag present! We remove this object:
00140                                         removeFromID(objectHandler->getID());
00141                                         i=-1; // ordering in _allObjects might have changed, we start from the beginning
00142                                 }
00143                         }
00144                 }
00145                 i++;
00146         }
00147 
00148         // 2. Now all GenericObjectHandler objects in this container are up-to-date. We now go through all objects in the scene
00149         // that have the QUADROTOR_DATA_MAIN tag, and check if they have a related GenericObjectHandler object in this container.
00150         // If not, we have to add a related GenericObjectHandler object:
00151 
00152         int objHandle=0;
00153         int ind=0;
00154         while (objHandle!=-1)
00155         {
00156                 objHandle=simGetObjects(ind++,sim_handle_all);
00157                 if (objHandle!=-1)
00158                 { // Scene object present at index ind
00159                         // Is that scene object already associated with a GenericObjectHandler object?
00160                         if (getFromAssociatedObject(objHandle)==NULL)
00161                         { // No, not yet
00162                                 // Does the object have a QUADROTOR_DATA_MAIN tag?
00163                                 // a. Get all the developer data attached to this object (this is custom data added by the developer):
00164                                 int buffSize=simGetObjectCustomDataLength(objHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER);
00165                                 char* datBuff=new char[buffSize];
00166                                 simGetObjectCustomData(objHandle, CustomDataHeaders::DEVELOPER_DATA_HEADER,datBuff);
00167                                 std::vector<unsigned char> developerCustomData(datBuff,datBuff+buffSize);
00168                                 delete[] datBuff;
00169                                 // b. From that retrieved data, try to extract sub-data with the QUADROTOR_DATA_MAIN tag:
00170                                 std::vector<unsigned char> tempMainData;
00171                                 bool objectFound = false;
00172 
00173                                 boost::shared_ptr<GenericObjectHandler> objectHandler;
00174 
00175                                 std::stringstream ss;
00176 
00177                                 for (std::map< std::string, boost::shared_ptr<GenericObjectHandler> >::iterator it = _allExistingPlugins.begin(); it!=_allExistingPlugins.end(); ++it){
00178                                 if ((objectFound = CAccess::extractSerializationData(developerCustomData, it->second->getObjectType(), tempMainData)) == true) {
00179                         // Yes, the tag is there. We have to add a new GenericObjectHandler object associated with this scene object:
00180                         try {
00181                             objectHandler = _object_handler_loader.createInstance(it->first);
00182                             insert(objectHandler);
00183                             int uniqueID;
00184                             simGetObjectUniqueIdentifier(objHandle,&uniqueID);
00185                             objectHandler->setAssociatedObject(objHandle,uniqueID);
00186                             objectHandler->synchronize();
00187                             ss << "Instantiating new " << it->first << " for "  << simGetObjectName(objHandle) << "." << std::endl;
00188                             ConsoleHandler::printInConsole(ss);
00189                         } catch(pluginlib::PluginlibException& ex){
00190                           //handle the class failing to load
00191                           ROS_ERROR("The plugin %s failed to load for some reason. Error: %s", it->first.c_str(), ex.what());
00192                         }
00193                     }
00194                             }
00195                         }
00196                 }
00197         }               
00198 }
00199 
00200 
00201 
00202 
00203 void GenericObjectContainer::simExtGetAllCustomData(SLuaCallBack* p){
00204     if (p->inputArgCount!=1){
00205         simSetLastError(pluginName,"This function requires 1 input argument.");
00206         return;
00207     }
00208 
00209     if (p->outputArgCount>1){
00210         simSetLastError(pluginName,"This function accepts 1 output argument.");
00211         return;
00212     }
00213 
00214     if(p->inputArgTypeAndSize[0]!=sim_lua_arg_int || p->inputInt[0]<0){
00215         simSetLastError(pluginName,"Wrong input argument type.");
00216         return;
00217     }
00218 
00219     if (p->outputArgCount==1 &&
00220             p->outputArgTypeAndSize[0]!=sim_lua_arg_string){
00221         simSetLastError(pluginName,"Wrong output argument type.");
00222         return;
00223     }
00224 
00225     // if inputs are correct go ahead
00226     const int objectHandle = p->inputInt[0];
00227 
00228 
00229     const uint buffSize=simGetObjectCustomDataLength(objectHandle, CustomDataHeaders::DEVELOPER_DATA_HEADER);
00230 
00231     if (buffSize<0){
00232         simSetLastError(pluginName,"The object does not contain any custom data for this plugin.");
00233         return;
00234     }
00235 
00236     std::vector<unsigned char> developerCustomData(buffSize);
00237     simGetObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,(simChar*)developerCustomData.data());
00238 
00239     std::stringstream ss;
00240     ss << "[";
00241     while (developerCustomData.size()>0){
00242         const int* dataHeader = ((int *)developerCustomData.data());
00243         const int* dataLength = ((int *)developerCustomData.data()+1);
00244         const unsigned char * data = developerCustomData.data()+2*sizeof(int);
00245 
00246         ss << std::dec << *dataHeader << ", " << *dataLength << ", ";
00247         if (*dataHeader == CustomDataHeaders::QUADROTOR_DATA_CTRL_MODE){
00248             ss << *((int *)data);
00249         } else if (*dataHeader == CustomDataHeaders::QUADROTOR_DATA_TF_RATIO){
00250             ss << *((float*)data);
00251         } else {
00252             ss << "0x";
00253             for (uint i=0; i<*dataLength; ++i){
00254                 ss << std::hex << std::setw(2) << std::setfill('0') << (int)data[i];
00255             }
00256         }
00257 
00258         developerCustomData.erase(developerCustomData.begin(), developerCustomData.begin()+2*sizeof(int)+*dataLength);
00259         if (developerCustomData.size()>0){
00260             ss << "; ";
00261         } else {
00262             ss << "]";
00263         }
00264     }
00265 
00266     p->outputArgCount=1; // 1 return value (function succeeded)
00267     p->outputArgTypeAndSize=(simInt*)simCreateBuffer(p->outputArgCount*2*sizeof(simInt));
00268     p->outputArgTypeAndSize[2*0+0]=sim_lua_arg_string;   // The first return value is an int
00269     p->outputArgTypeAndSize[2*0+1]=sim_lua_arg_nil;     // Not used (table size if the return value was a table)
00270     p->outputChar=(simChar*)simCreateBuffer(ss.str().size()+1);
00271     strcpy(p->outputChar,ss.str().c_str());
00272 }
00273 
00274 
00275 void GenericObjectContainer::simExtGetCustomDataFromHeader(SLuaCallBack* p){
00276     if (p->inputArgCount!=2){
00277         simSetLastError(pluginName,"This function requires 2 input arguments.");
00278         return;
00279     }
00280 
00281     if (p->outputArgCount>1){
00282         simSetLastError(pluginName,"This function accepts 1 output argument.");
00283         return;
00284     }
00285 
00286     if(p->inputArgTypeAndSize[0]!=sim_lua_arg_int || p->inputInt[0]<0 ||
00287             p->inputArgTypeAndSize[2]!=sim_lua_arg_int){
00288         simSetLastError(pluginName,"Wrong input argument type.");
00289         return;
00290     }
00291 
00292     if (p->outputArgCount==1 &&
00293             p->outputArgTypeAndSize[0]!=sim_lua_arg_float){
00294         simSetLastError(pluginName,"Wrong output argument type.");
00295         return;
00296     }
00297 
00298     // if inputs are correct go ahead
00299     const int objectHandle = p->inputInt[0];
00300     const int dataHeader = p->inputInt[1];
00301 
00302     const uint buffSize=simGetObjectCustomDataLength(objectHandle, CustomDataHeaders::DEVELOPER_DATA_HEADER);
00303 
00304     if (buffSize<0){
00305         simSetLastError(pluginName,"The object does not contain any custom data for this plugin.");
00306         return;
00307     }
00308 
00309     std::vector<unsigned char> developerCustomData(buffSize);
00310     simGetObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,(simChar*)developerCustomData.data());
00311 
00312     std::vector<unsigned char> tempData;
00313 
00314     if(CAccess::extractSerializationData(developerCustomData, dataHeader, tempData)){
00315         p->outputArgCount=1; // 1 return value (function succeeded)
00316         p->outputArgTypeAndSize=(simInt*)simCreateBuffer(p->outputArgCount*2*sizeof(simInt)); // x return values takes x*2 simInt for the type and size buffer
00317         p->outputArgTypeAndSize[1]=sim_lua_arg_nil;     // Not used (table size if the return value was a table)
00318 
00319         if (dataHeader == CustomDataHeaders::QUADROTOR_DATA_CTRL_MODE){
00320             p->outputArgTypeAndSize[0]=sim_lua_arg_int;   // The first return value is a float
00321             p->outputInt=(simInt*)simCreateBuffer(1*sizeof(simInt)); // 1 float return value
00322             p->outputInt[0] = (simInt)CAccess::pop_int(tempData);
00323 
00324         } else {
00325             p->outputArgTypeAndSize[0]=sim_lua_arg_float;   // The first return value is a float
00326             p->outputFloat=(simFloat*)simCreateBuffer(1*sizeof(simFloat)); // 1 float return value
00327             p->outputFloat[0] = (simFloat)CAccess::pop_float(tempData);
00328         }
00329     } else {
00330         p->outputArgCount=0; // 1 return value (function succeeded)
00331         simSetLastError(pluginName,"The data was not found.");
00332     }
00333 }
00334 
00335 
00336 simVoid GenericObjectContainer::simExtSetFloatCustomDataFromHeader(SLuaCallBack* p){
00337 
00338     if (p->inputArgCount!=3){
00339         simSetLastError(pluginName,"This function requires 2 input arguments.");
00340         return;
00341     }
00342 
00343     if (p->outputArgCount>1){
00344         simSetLastError(pluginName,"This function accepts 1 output argument.");
00345         return;
00346     }
00347 
00348     if(p->inputArgTypeAndSize[0]!=sim_lua_arg_int || p->inputInt[0]<0 ||
00349             p->inputArgTypeAndSize[2]!=sim_lua_arg_int ||
00350             p->inputArgTypeAndSize[4]!=sim_lua_arg_float){
00351         simSetLastError(pluginName,"Wrong input argument type.");
00352         return;
00353     }
00354 
00355     if (p->outputArgCount==1 &&
00356             p->outputArgTypeAndSize[0]!=sim_lua_arg_float){
00357         simSetLastError(pluginName,"Wrong output argument type.");
00358         return;
00359     }
00360 
00361     // if inputs are correct go ahead
00362     const int objectHandle = p->inputInt[0];
00363     const int dataHeader = p->inputInt[1];
00364 
00365     const uint buffSize=simGetObjectCustomDataLength(objectHandle, CustomDataHeaders::DEVELOPER_DATA_HEADER);
00366 
00367     if (buffSize<0){
00368         simSetLastError(pluginName,"Error getting custom data from the object.");
00369         return;
00370     }
00371 
00372     std::vector<unsigned char> developerCustomData(buffSize);
00373     simGetObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,(simChar*)developerCustomData.data());
00374 
00375     // 2. From that retrieved data, extract sub-data with the dataHeader tag, update it, and add it back to the retrieved data:
00376     std::vector<unsigned char> tempData;
00377     CAccess::extractSerializationData(developerCustomData, dataHeader, tempData);
00378 
00379     tempData.clear(); // we discard the old value (if present)
00380 
00381     const float dataValue = p->inputFloat[0];
00382     CAccess::push_float(tempData, dataValue); // we replace it with the new value
00383 
00384     CAccess::insertSerializationData(developerCustomData,dataHeader,tempData);
00385 
00386     // 3. We add/update the scene object with the updated custom data:
00387     simAddObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,
00388             (simChar*)developerCustomData.data(),int(developerCustomData.size()));
00389 
00391 //    std::vector<unsigned char> tempData;
00392 //    if(extractSerializationData(developerCustomData, dataHeader, tempData)){
00393 //
00394 //        p->outputArgCount=1; // 1 return value (function succeeded)
00395 //
00396 //        p->outputArgTypeAndSize=(simInt*)simCreateBuffer(p->outputArgCount*2*sizeof(simInt)); // x return values takes x*2 simInt for the type and size buffer
00397 //
00398 //        p->outputArgTypeAndSize[2*0+0]=sim_lua_arg_float;   // The first return value is an int
00399 //        p->outputArgTypeAndSize[2*0+1]=sim_lua_arg_nil;     // Not used (table size if the return value was a table)
00400 //
00401 //        p->outputFloat=(simFloat*)simCreateBuffer(1*sizeof(simFloat)); // 1 float return value
00402 //        p->outputFloat[0] = (simFloat)CAccess::pop_float(tempData);
00403 //    } else {
00404 //        simSetLastError(pluginName,"The data was not found.");
00405 //    }
00406 }
00407 
00408 
00409 
00410 simVoid GenericObjectContainer::simExtSetIntCustomDataFromHeader(SLuaCallBack* p){
00411 
00412     if (p->inputArgCount!=3){
00413         simSetLastError(pluginName,"This function requires 2 input arguments.");
00414         return;
00415     }
00416 
00417     if (p->outputArgCount>1){
00418         simSetLastError(pluginName,"This function accepts 1 output argument.");
00419         return;
00420     }
00421 
00422     if(p->inputArgTypeAndSize[0]!=sim_lua_arg_int || p->inputInt[0]<0 ||
00423             p->inputArgTypeAndSize[2]!=sim_lua_arg_int ||
00424             p->inputArgTypeAndSize[4]!=sim_lua_arg_int){
00425         simSetLastError(pluginName,"Wrong input argument type.");
00426         return;
00427     }
00428 
00429     if (p->outputArgCount==1 &&
00430             p->outputArgTypeAndSize[0]!=sim_lua_arg_float){
00431         simSetLastError(pluginName,"Wrong output argument type.");
00432         return;
00433     }
00434 
00435     // if inputs are correct go ahead
00436     const int objectHandle = p->inputInt[0];
00437     const int dataHeader = p->inputInt[1];
00438 
00439     const uint buffSize=simGetObjectCustomDataLength(objectHandle, CustomDataHeaders::DEVELOPER_DATA_HEADER);
00440 
00441     if (buffSize<0){
00442         simSetLastError(pluginName,"Error getting custom data from the object.");
00443         return;
00444     }
00445 
00446     std::vector<unsigned char> developerCustomData(buffSize);
00447     simGetObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,(simChar*)developerCustomData.data());
00448 
00449     // 2. From that retrieved data, extract sub-data with the dataHeader tag, update it, and add it back to the retrieved data:
00450     std::vector<unsigned char> tempData;
00451     CAccess::extractSerializationData(developerCustomData, dataHeader, tempData);
00452 
00453     tempData.clear(); // we discard the old value (if present)
00454 
00455     const int dataValue = p->inputInt[2];
00456     CAccess::push_int(tempData, dataValue); // we replace it with the new value
00457 
00458     CAccess::insertSerializationData(developerCustomData,dataHeader,tempData);
00459 
00460     // 3. We add/update the scene object with the updated custom data:
00461     simAddObjectCustomData(objectHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,
00462             (simChar*)developerCustomData.data(),int(developerCustomData.size()));
00463 
00465 //    std::vector<unsigned char> tempData;
00466 //    if(extractSerializationData(developerCustomData, dataHeader, tempData)){
00467 //
00468 //        p->outputArgCount=1; // 1 return value (function succeeded)
00469 //
00470 //        p->outputArgTypeAndSize=(simInt*)simCreateBuffer(p->outputArgCount*2*sizeof(simInt)); // x return values takes x*2 simInt for the type and size buffer
00471 //
00472 //        p->outputArgTypeAndSize[2*0+0]=sim_lua_arg_float;   // The first return value is an int
00473 //        p->outputArgTypeAndSize[2*0+1]=sim_lua_arg_nil;     // Not used (table size if the return value was a table)
00474 //
00475 //        p->outputFloat=(simFloat*)simCreateBuffer(1*sizeof(simFloat)); // 1 float return value
00476 //        p->outputFloat[0] = (simFloat)CAccess::pop_float(tempData);
00477 //    } else {
00478 //        simSetLastError(pluginName,"The data was not found.");
00479 //    }
00480 }
00481 
00482 
00483 
00484 
00485 


vrep_ros_plugin
Author(s): Riccardo Spica , Giovanni Claudio
autogenerated on Wed Sep 9 2015 18:54:51