main.cpp
Go to the documentation of this file.
00001 #include <rtt/os/main.h>
00002 
00003 #include <boost/program_options.hpp>
00004 #include <iostream>
00005 #include <rtt/internal/GlobalEngine.hpp>
00006 #include <rtt/TaskContext.hpp>
00007 
00008 <% if deployer.corba_enabled? %>
00009 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00010 #include <service_discovery/ServiceDiscovery.hpp>
00011 #endif // OROGEN_SERVICE_DISCOVERY_ACTIVATED
00012 <% end %>
00013 
00014 #include <rtt/typekit/RealTimeTypekit.hpp>
00015 <% if deployer.transports.include?('corba') %>
00016 #include <rtt/transports/corba/TransportPlugin.hpp>
00017 <% end %>
00018 <% if deployer.transports.include?('mqueue') %>
00019 #include <rtt/transports/mqueue/TransportPlugin.hpp>
00020 <% end %>
00021 
00022 <% if project.typekit || !project.used_typekits.empty? %>
00023 #include <rtt/types/TypekitPlugin.hpp>
00024 <% end %>
00025 <% if typekit = project.typekit %>
00026 #include <<%= typekit.name %>/typekit/Plugin.hpp>
00027 <% deployer.transports.each do |transport_name| %>
00028 #include "typekit/transports/<%= transport_name %>/TransportPlugin.hpp"
00029 <% end %>
00030 <% end %>
00031 <% deployer.used_typekits.each do |tk| %>
00032     <% next if tk.virtual? %>
00033 #include <<%= tk.name %>/typekit/Plugin.hpp>
00034     <% deployer.transports.each do |transport_name| %>
00035 #include <<%= tk.name %>/transports/<%= transport_name %>/TransportPlugin.hpp>
00036     <% end %>
00037 <% end %>
00038 
00039 <% task_activities = deployer.task_activities.sort_by(&:name) %>
00040 <% if deployer.corba_enabled? %>
00041 #include <rtt/transports/corba/ApplicationServer.hpp>
00042 #include <rtt/transports/corba/TaskContextServer.hpp>
00043 #include <rtt/transports/corba/CorbaDispatcher.hpp>
00044 #include <signal.h>
00045 <% end %>
00046 <% if deployer.transports.include? 'ros' %>
00047 #include <ros/ros.h>
00048 <% end %>
00049 
00050 <% require 'set'
00051     activity_headers = task_activities.
00052         map { |t| t.activity_type.header }.
00053         compact.
00054         to_set %>
00055 <% activity_headers.to_a.sort.each do |header| %>
00056 #include <<%= header %>>
00057 <% end %>
00058 
00059 <% if deployer.browse %>
00060 #include <ocl/TaskBrowser.hpp>
00061 <% end %>
00062 #include <rtt/Logger.hpp>
00063 #include <rtt/base/ActivityInterface.hpp>
00064 
00065 namespace orogen
00066 {
00067 <% task_activities.each do |task| %>
00068     extern RTT::TaskContext* create_<%= task.task_model.name.gsub(/[^\w]/, '_') %>(std::string const& instance_name);
00069 <% end %>
00070 }
00071 
00072 namespace po = boost::program_options;
00073 
00074 class Deinitializer
00075 {
00076     friend Deinitializer& operator << (Deinitializer&, RTT::base::ActivityInterface&);
00077 
00078     std::vector<RTT::base::ActivityInterface*> m_activities;
00079 
00080 <% if deployer.corba_enabled? %>
00081 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00082     friend Deinitializer& operator << (Deinitializer&, servicediscovery::avahi::ServiceDiscovery&);
00083 
00084     std::vector<servicediscovery::avahi::ServiceDiscovery*> m_service_discoveries;
00085 #endif
00086 <% end %>
00087 
00088 
00089 public:
00090     ~Deinitializer()
00091     {
00092         for (std::vector<RTT::base::ActivityInterface*>::const_iterator it = m_activities.begin();
00093                 it != m_activities.end(); ++it)
00094         {
00095             (*it)->stop();
00096         }
00097 
00098 <% if deployer.corba_enabled? %>
00099 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00100         for(std::vector<servicediscovery::avahi::ServiceDiscovery*>::iterator sit = m_service_discoveries.begin();
00101                 sit != m_service_discoveries.end(); ++sit)
00102         {
00103             (*sit)->stop();
00104             delete *sit;
00105         }
00106 #endif 
00107 <% end %>
00108     }
00109 };
00110 
00111 Deinitializer& operator << (Deinitializer& deinit, RTT::base::ActivityInterface& activity)
00112 {
00113     deinit.m_activities.push_back(&activity);
00114     return deinit;
00115 }
00116 
00117 <% if deployer.corba_enabled? %>
00118 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00119 Deinitializer& operator << (Deinitializer& deinit, servicediscovery::avahi::ServiceDiscovery& service_discovery)
00120 {
00121     deinit.m_service_discoveries.push_back(&service_discovery);
00122     return deinit;
00123 }
00124 #endif 
00125 <% end %>
00126 
00127 <% if deployer.corba_enabled? %>
00128 int sigint_com[2];
00129 void sigint_quit_orb(int)
00130 {
00131     uint8_t dummy = 0;
00132     unsigned int sent = 0;
00133     while(sent < sizeof(uint8_t))
00134     {
00135         int ret = write(sigint_com[1], &dummy, sizeof(uint8_t));
00136         if(ret < 0)
00137         {
00138             std::cerr << "Failed to signal quit to orb" << std::endl;
00139             break;
00140         }
00141         sent += ret;
00142     }
00143 }
00144 <% end %>
00145 
00146 int ORO_main(int argc, char* argv[])
00147 {
00148    po::options_description desc("Options");
00149 
00150    desc.add_options()
00151         ("help", "show all available options supported by this deployment")
00152         ("prefix", po::value<std::string>(), "Sets a prefix for all TaskContext names")
00153 <% if deployer.corba_enabled? %>
00154 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00155         ("sd-domain", po::value<std::string>(), "set service discovery domain")
00156 #endif // OROGEN_SERVICE_DISOCVERY_ACTIVATED
00157 <% end %>
00158         ("with-ros", po::value<bool>()->default_value(false), "also publish the task as ROS node, default is false")
00159         ("rename", po::value< std::vector<std::string> >(), "rename a task of the deployment: --rename oldname:newname");
00160 
00161    po::variables_map vm;
00162    po::store(po::parse_command_line(argc, argv, desc), vm);
00163    po::notify(vm);
00164 
00165    if(vm.count("help")) {
00166        std::cout << desc << std::endl;
00167        return 0;
00168    }
00169 
00170 
00171    <% if deployer.loglevel %>
00172    if ( log().getLogLevel() < Logger::<%= deployer.loglevel %> ) {
00173        log().setLogLevel( Logger::<%= deployer.loglevel %> );
00174    }
00175    <% end %>
00176 
00177    RTT::types::TypekitRepository::Import( new RTT::types::RealTimeTypekitPlugin );
00178    <% if deployer.transports.include?('corba') %>
00179    RTT::types::TypekitRepository::Import( new RTT::corba::CorbaLibPlugin );
00180    <% end %>
00181    <% if deployer.transports.include?('mqueue') %>
00182    RTT::types::TypekitRepository::Import( new RTT::mqueue::MQLibPlugin );
00183    <% end %>
00184 
00185    <% if project.typekit %>
00186    RTT::types::TypekitRepository::Import( new orogen_typekits::<%= project.name %>TypekitPlugin );
00187    <% deployer.transports.each do |transport_name| %>
00188    RTT::types::TypekitRepository::Import( new <%= typekit.transport_plugin_name(transport_name) %> );
00189    <% end %>
00190    <% end %>
00191    <% deployer.used_typekits.each do |tk| %>
00192    <% next if tk.virtual? %>
00193    RTT::types::TypekitRepository::Import( new orogen_typekits::<%= tk.name %>TypekitPlugin );
00194        <% deployer.transports.each do |transport_name| %>
00195    RTT::types::TypekitRepository::Import( new <%= RTT_CPP::Typekit.transport_plugin_name(transport_name, tk.name) %> );
00196        <% end %>
00197    <% end %>
00198 
00199 <% if deployer.corba_enabled? %>
00200     RTT::corba::ApplicationServer::InitOrb(argc, argv);
00201 <% end %>
00202 
00203     std::string prefix = "";
00204 
00205     if( vm.count("prefix")) 
00206         prefix = vm["prefix"].as<std::string>();
00207 
00208     bool with_ros = false;
00209 
00210     if( vm.count("with-ros"))
00211         with_ros = vm["with-ros"].as<bool>();
00212 
00213     std::string task_name;
00214 
00215     std::map<std::string, std::string> rename_map;
00216 
00217     if ( vm.count("rename") ) {
00218 
00219         const std::vector< std::string>& ren_vec = vm["rename"].as<std::vector <std::string> >();
00220 
00221         for ( unsigned int i = 0; i < ren_vec.size(); i++) {
00222 
00223             const std::string& ren_str = ren_vec.at(i);
00224 
00225             unsigned int colon_pos = ren_str.find(':');
00226             if ( colon_pos == std::string::npos ) continue;
00227 
00228             rename_map.insert( std::pair<std::string, std::string>( 
00229                 ren_str.substr(0,colon_pos), ren_str.substr(colon_pos+1) ));
00230         }
00231     }    
00232    
00233 <% if lock_timeout = deployer.get_lock_timeout_no_period %>
00234     RTT::os::Thread::setLockTimeoutNoPeriod(<%= lock_timeout %>);
00235 <% end %>
00236 
00237 <% if lock_factor = deployer.get_lock_timeout_period_factor %>
00238     RTT::os::Thread::setLockTimeoutPeriodFactor(<%= lock_factor %>);
00239 <% end %>
00240 
00241 // Initialize some global threads so that we can properly setup their threading
00242 // parameters
00243 <% has_realtime = task_activities.all? { |t| t.realtime? } %>
00244 <% if has_realtime %>
00245 RTT::internal::GlobalEngine::Instance(ORO_SCHED_RT, RTT::os::LowestPriority);
00246 <% else %>
00247 RTT::internal::GlobalEngine::Instance(ORO_SCHED_OTHER, RTT::os::LowestPriority);
00248 <% end %>
00249 
00250 //First Create all Tasks to be able to set some (slave-) activities later on in the second loop
00251 <% task_activities.each do |task| %>
00252     task_name = "<%= task.name %>";
00253     if (rename_map.count(task_name))
00254         task_name = rename_map[task_name];
00255     else
00256         task_name = prefix + task_name;
00257     
00258     std::auto_ptr<RTT::TaskContext> task_<%= task.name%>(
00259             orogen::create_<%= task.task_model.name.gsub(/[^\w]/, '_') %>(task_name));
00260 
00261     <% if deployer.corba_enabled? %>
00262     RTT::corba::TaskContextServer::Create( task_<%= task.name %>.get() );
00263     <% if task.realtime? %>
00264     RTT::corba::CorbaDispatcher::Instance( task_<%= task.name %>->ports(), ORO_SCHED_RT, RTT::os::LowestPriority );
00265     <% else %>
00266     RTT::corba::CorbaDispatcher::Instance( task_<%= task.name %>->ports(), ORO_SCHED_OTHER, RTT::os::LowestPriority );
00267     <% end %>
00268     <% end %>
00269 
00270 <% end %>
00271 
00272 //Create all Activities afterwards to be sure all tasks are created. The Activitied are also handeld by the deployment because
00273 //the order needs to be known since slav activities are useable
00274 //
00275 <% activity_ordered_tasks.each do |task| %>
00276     <%= task.generate_activity_setup %>
00277     <% if timeout = task.stop_timeout %>
00278     { RTT::os::Thread* thread = dynamic_cast<RTT::os::Thread*>(activity_<%= task.name %>);
00279         if (thread)
00280             thread->setStopTimeout(<%= timeout %>);
00281     }
00282     <% end %>
00283     task_<%= task.name %>->setActivity(activity_<%= task.name %>);
00284 <% end %>
00285 
00286 
00287 
00288    Deinitializer deinit;
00289 
00290 <% if deployer.corba_enabled? %>
00291 #ifdef OROGEN_SERVICE_DISCOVERY_ACTIVATED
00292     if( vm.count("sd-domain") ) {
00293 <% task_activities.each do |task| %>
00294     servicediscovery::avahi::ServiceConfiguration sd_conf_<%= task.name%>(task_<%= task.name%>->getName(), vm["sd-domain"].as<std::string>());
00295     sd_conf_<%= task.name%>.setDescription("IOR", RTT::corba::TaskContextServer::getIOR(task_<%= task.name%>.get()));
00296     sd_conf_<%= task.name%>.setDescription("TASK_MODEL","<%= task.task_model.name %>");
00297     servicediscovery::avahi::ServiceDiscovery* sd_<%= task.name%> = new servicediscovery::avahi::ServiceDiscovery();
00298     deinit << *sd_<%= task.name%>;
00299     sd_<%= task.name%>->start(sd_conf_<%= task.name%>);
00300 <% end %>
00301     }
00302 #endif // OROGEN_SERVICE_DISCOVERY_ACTIVATED
00303 <% end %>
00304 
00305 <% all_peers = deployer.peers.dup.to_a
00306    all_peers.concat deployer.each_task.inject(Array.new) { |a, m| a.concat m.slaves.map { |s| [m, s] } }
00307    all_peers.sort_by { |a, b| [a.name, b.name] }.each do |a, b| %>
00308     task_<%= a.name %>->connectPeers(task_<%= b.name %>.get());
00309 <% end %>
00310 
00311 <% deployer.connections.
00312     sort_by { |src, dst, policy| [src.name, dst.name] }.
00313     each do |src, dst, policy|
00314         if src.kind_of?(Spec::TaskDeployment) %>
00315             task_<%= src.activity.name %>->connectPorts(task_<%= dst.activity.name %>.get());
00316         <% else %>
00317         {
00318             <%= policy.to_code("policy") %>
00319             RTT::base::OutputPortInterface* src = dynamic_cast<RTT::base::OutputPortInterface*>(
00320                     task_<%= src.activity.name %>->ports()->getPort("<%= src.name %>"));
00321             RTT::base::InputPortInterface* dst = dynamic_cast<RTT::base::InputPortInterface*>(
00322                     task_<%= dst.activity.name %>->ports()->getPort("<%= dst.name %>"));
00323             src->createConnection(*dst, policy);
00324         }
00325         <% end %>
00326     <% end %>
00327 
00328     // Start some activities
00329 <% task_activities.each do |task| %>
00330     deinit << *activity_<%= task.name%>;
00331 
00332     <% if task.start?
00333         if task.context.needs_configuration? %>
00334     if (!task_<%= task.name %>->configure())
00335     {
00336         RTT::log(RTT::Error) << "cannot configure <%= task.name %>" << RTT::endlog();
00337         return -1;
00338     }
00339         <% end %>
00340     if (!task_<%= task.name %>->start())
00341     {
00342         RTT::log(RTT::Error) << "cannot start <%= task.name %>" << RTT::endlog();
00343         return -1;
00344     }
00345     <% end %>
00346 <% end %>
00347 
00348     if(with_ros){
00349 <% if deployer.transports.include? 'ros' %>
00350         RTT::log(RTT::Info)<<"Initializing ROS node"<<RTT::endlog();
00351         if(!ros::isInitialized()){
00352             int argc =__os_main_argc();
00353             char ** argv = __os_main_argv();
00354             ros::init(argc,argv,prefix + "<%= deployer.name %>");
00355           if(ros::master::check())
00356               ros::start();
00357           else{
00358               RTT::log(RTT::Error)<<"No ros::master available"<<RTT::endlog();
00359               return false;
00360           }
00361         }
00362         static ros::AsyncSpinner spinner(1); // Use 1 threads
00363         spinner.start();
00364         RTT::log(RTT::Info)<<"ROS node spinner started"<<RTT::endlog();
00365 <% else %>
00366         throw std::runtime_error("Requesting to start as ROS node, but the support for 'ros' transport is not available. Recompile with 'ros' transport option!");
00367 <% end %>
00368     }
00369 
00370 <% if deployer.corba_enabled? %>
00373     if (pipe(sigint_com) == -1)
00374     {
00375         std::cerr << "failed to setup SIGINT handler: " << strerror(errno) << std::endl;
00376         return 1;
00377     }
00378 
00379     struct sigaction sigint_handler;
00380     sigint_handler.sa_handler = &sigint_quit_orb;
00381     sigemptyset(&sigint_handler.sa_mask);
00382     sigint_handler.sa_flags     = 0;
00383     sigint_handler.sa_restorer  = 0;
00384     if (-1 == sigaction(SIGINT, &sigint_handler, 0))
00385     {
00386         std::cerr << "failed to install SIGINT handler" << std::endl;
00387         return 1;
00388     }
00389     sigset_t unblock_sigint;
00390     sigemptyset(&unblock_sigint);
00391     sigaddset(&unblock_sigint, SIGINT);
00392     if (-1 == sigprocmask(SIG_UNBLOCK, &unblock_sigint, NULL))
00393     {
00394         std::cerr << "failed to install SIGINT handler" << std::endl;
00395         return 1;
00396     }
00397     <% if has_realtime %>
00398     RTT::corba::TaskContextServer::ThreadOrb(ORO_SCHED_RT, RTT::os::LowestPriority, 0);
00399     <% else %>
00400     RTT::corba::TaskContextServer::ThreadOrb(ORO_SCHED_OTHER, RTT::os::LowestPriority, 0);
00401     <% end %>
00402     while (true)
00403     {
00404         uint8_t dummy;
00405         int read_count = read(sigint_com[0], &dummy, 1);
00406         if (read_count == 1)
00407             break;
00408     }
00409 
00410     RTT::corba::TaskContextServer::ShutdownOrb();
00411     RTT::corba::TaskContextServer::DestroyOrb();
00412 <% elsif deployer.browse %>
00413     OCL::TaskBrowser browser(task_<%= deployer.browse.name %>.get());
00414     browser.loop();
00415 <% end %>
00416 
00417     return 0;
00418 }
00419 


orogen
Author(s): Sylvain Joyeux/sylvain.joyeux@m4x.org
autogenerated on Sat Jun 8 2019 19:52:17