Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026 #include "plugindefs.h"
00027
00028 #include "objecttransformsystem.h"
00029 #include "rosbindings.h"
00030 #include "collisionmapsystem.h"
00031
00032 #include <openrave/plugin.h>
00033
00034 ControllerBasePtr CreateROSPassiveController(EnvironmentBasePtr penv, std::istream& sinput);
00035
00036 static list< boost::shared_ptr<void> >* s_listRegisteredReaders = NULL;
00037 InterfaceBasePtr CreateInterfaceValidated(InterfaceType type, const std::string& interfacename, std::istream& sinput, EnvironmentBasePtr penv)
00038 {
00039 if( !s_listRegisteredReaders ) {
00040 s_listRegisteredReaders = new list< boost::shared_ptr<void> >();
00041 s_listRegisteredReaders->push_back(ObjectTransformSystem::RegisterXMLReader(penv));
00042 s_listRegisteredReaders->push_back(CollisionMapSystem::RegisterXMLReader(penv));
00043 }
00044 switch(type) {
00045 case PT_SensorSystem:
00046 if( interfacename == "objecttransform" ) {
00047 boost::shared_ptr<ObjectTransformSystem> psys(new ObjectTransformSystem(penv));
00048 if( !psys->Init(sinput) ) {
00049 RAVELOG_WARN(str(boost::format("failed to init %s\n")%interfacename));
00050 }
00051 return psys;
00052 }
00053 else if( interfacename == "collisionmap" ) {
00054 boost::shared_ptr<CollisionMapSystem> psys(new CollisionMapSystem(penv));
00055 if( !psys->Init(sinput) ) {
00056 RAVELOG_WARN(str(boost::format("failed to init %s\n")%interfacename));
00057 }
00058 return psys;
00059 }
00060 break;
00061 case PT_ProblemInstance:
00062 if( interfacename == "rosbindings" ) {
00063 return InterfaceBasePtr(new ROSBindings(penv));
00064 }
00065 break;
00066 case PT_Controller:
00067 if( interfacename == "rospassivecontroller" ) {
00068 return CreateROSPassiveController(penv,sinput);
00069 }
00070 break;
00071 default:
00072 break;
00073 }
00074 return InterfaceBasePtr();
00075 }
00076
00077 void GetPluginAttributesValidated(PLUGININFO& info)
00078 {
00079 info.interfacenames[OpenRAVE::PT_SensorSystem].push_back("ObjectTransform");
00080 info.interfacenames[OpenRAVE::PT_SensorSystem].push_back("CollisionMap");
00081 info.interfacenames[OpenRAVE::PT_ProblemInstance].push_back("ROSBindings");
00082 info.interfacenames[OpenRAVE::PT_Controller].push_back("ROSPassiveController");
00083 }
00084
00085 OPENRAVE_PLUGIN_API void DestroyPlugin()
00086 {
00087 delete s_listRegisteredReaders;
00088 s_listRegisteredReaders = NULL;
00089 }