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 
00027 
00028 
00029 #include <rtt/plugin/Plugin.hpp>
00030 #include <rtt/TaskContext.hpp>
00031 #include <rtt/Activity.hpp>
00032 #include <rtt/Logger.hpp>
00033 #include <rtt/os/startstop.h>
00034 #include <ros/ros.h>
00035 
00036 using namespace RTT;
00037 
00038 extern "C" {
00039   bool loadRTTPlugin(RTT::TaskContext* c){
00040 
00041     
00042     if (!ros::isInitialized()) {
00043       log(Info) << "Initializing ROS node in Orocos plugin..." << endlog();
00044 
00045       int argc = __os_main_argc();
00046       char ** argv = __os_main_argv();
00047 
00048       
00049       
00050       
00051       
00052       
00053       std::vector<char *> argvv(argv, argv + argc);
00054       assert(argvv.size() == argc);
00055       ros::init(argc, argvv.data(), "rtt", ros::init_options::AnonymousName);
00056       argvv.resize(argc);
00057 
00058       if (ros::master::check()) {
00059         ros::start();
00060       } else {
00061         log(Warning) << "'roscore' is not running: no ROS functions will be available." << endlog();
00062         ros::shutdown();
00063         return true;
00064       }
00065     }
00066 
00067     
00068     int thread_count = 1;
00069     ros::param::get("~spinner_threads", thread_count);
00070 
00071     
00072     static ros::AsyncSpinner spinner(thread_count); 
00073 
00074     
00075     spinner.start();
00076     log(Info) << "ROS node spinner started (" << thread_count << " " << (thread_count > 1 ? "threads" : "thread") << ")." << endlog();
00077 
00078     return true;
00079   }
00080 
00081   std::string getRTTPluginName () {
00082     return "rosnode";
00083   }
00084 
00085   std::string getRTTTargetName () {
00086     return OROCOS_TARGET_NAME;
00087   }
00088 }
00089