00001 #include <rtt/os/main.h>
00002
00003 #include <rtt/typekit/RealTimeTypekit.hpp>
00004 <% deployer.rtt_transports.each do |transport_name| %>
00005 #include <rtt/transports/<%= transport_name %>/TransportPlugin.hpp>
00006 <% end %>
00007
00008 <% if component.typekit || !component.used_typekits.empty? %>#include <rtt/types/TypekitPlugin.hpp><% end %>
00009 <% if typekit = component.typekit %>
00010 #include "typekit/Plugin.hpp"
00011 <% deployer.transports.each do |transport_name| %>
00012 #include "typekit/transports/<%= transport_name %>/TransportPlugin.hpp"
00013 <% end %>
00014 <% end %>
00015 <% deployer.used_typekits.each do |tk| %>
00016 <% next if tk.virtual? %>
00017 #include <<%= tk.name %>/typekit/Plugin.hpp>
00018 <% deployer.transports.each do |transport_name| %>
00019 #include <<%= tk.name %>/transports/<%= transport_name %>/TransportPlugin.hpp>
00020 <% end %>
00021 <% end %>
00022
00023 <% task_activities = deployer.task_activities.
00024 sort_by(&:name) %>
00025
00026 <% task_activities.each do |task| %>
00027 #include <<%= task.context.header_file %>>
00028 <% end %>
00029 <% if deployer.corba_enabled? %>
00030 #include <rtt/transports/corba/ApplicationServer.hpp>
00031 #include <rtt/transports/corba/TaskContextServer.hpp>
00032 #include <signal.h>
00033 <% end %>
00034
00035 <% require 'set'
00036 activity_headers = task_activities.
00037 map { |t| t.activity_type.header }.
00038 compact.
00039 to_set %>
00040 <% activity_headers.to_a.sort.each do |header| %>
00041 #include <<%= header %>>
00042 <% end %>
00043
00044 <% if deployer.browse %>
00045 #include <ocl/TaskBrowser.hpp>
00046 <% end %>
00047
00048 #include <rtt/Logger.hpp>
00049 #include <rtt/base/ActivityInterface.hpp>
00050 class Deinitializer
00051 {
00052 friend Deinitializer& operator << (Deinitializer&, RTT::base::ActivityInterface&);
00053
00054 std::vector<RTT::base::ActivityInterface*> m_activities;
00055
00056 public:
00057 ~Deinitializer()
00058 {
00059 for (std::vector<RTT::base::ActivityInterface*>::const_iterator it = m_activities.begin();
00060 it != m_activities.end(); ++it)
00061 {
00062 (*it)->stop();
00063 }
00064 }
00065 };
00066
00067 Deinitializer& operator << (Deinitializer& deinit, RTT::base::ActivityInterface& activity)
00068 {
00069 deinit.m_activities.push_back(&activity);
00070 return deinit;
00071 }
00072
00073 <% if deployer.corba_enabled? %>
00074 void sigint_quit_orb(int)
00075 {
00076 RTT::corba::TaskContextServer::ShutdownOrb(false);
00077 }
00078 <% end %>
00079
00080 int ORO_main(int argc, char* argv[])
00081 {
00082 <% if deployer.loglevel %>
00083 if ( log().getLogLevel() < Logger::<%= deployer.loglevel %> ) {
00084 log().setLogLevel( Logger::<%= deployer.loglevel %> );
00085 }
00086 <% end %>
00087
00088 RTT::types::TypekitRepository::Import( new RTT::types::RealTimeTypekitPlugin );
00089 <% if deployer.transports.include?('corba') %>
00090 RTT::types::TypekitRepository::Import( new RTT::corba::CorbaLibPlugin );
00091 <% end %>
00092 <% if deployer.transports.include?('mqueue') %>
00093 RTT::types::TypekitRepository::Import( new RTT::mqueue::MQLibPlugin );
00094 <% end %>
00095
00096 <% if component.typekit %>
00097 RTT::types::TypekitRepository::Import( new orogen_typekits::<%= component.name %>TypekitPlugin );
00098 <% deployer.transports.each do |transport_name| %>
00099 RTT::types::TypekitRepository::Import( new <%= typekit.transport_plugin_name(transport_name) %> );
00100 <% end %>
00101 <% end %>
00102 <% deployer.used_typekits.each do |tk| %>
00103 <% next if tk.virtual? %>
00104 RTT::types::TypekitRepository::Import( new orogen_typekits::<%= tk.name %>TypekitPlugin );
00105 <% deployer.transports.each do |transport_name| %>
00106 RTT::types::TypekitRepository::Import( new <%= Orocos::Generation::Typekit.transport_plugin_name(transport_name, tk.name) %> );
00107 <% end %>
00108 <% end %>
00109
00110 <% if deployer.corba_enabled? %>
00111 RTT::corba::ApplicationServer::InitOrb(argc, argv);
00112 <% end %>
00113
00114 <% task_activities.each do |task| %>
00115 <%= task.context.class_name %> task_<%= task.name%>("<%= task.name %>");
00116 <%= task.generate_activity_setup %>
00117 task_<%= task.name %>.setActivity(activity_<%= task.name %>);
00118 <% task.properties.sort_by { |prop| prop.name }.each do |prop|
00119 if prop.value %>
00120 dynamic_cast< RTT::Property< <%= prop.interface_object.type.cxx_name %> >*>(
00121 task_<%= task.name %>.properties()->getProperty("<%= prop.name %>"))
00122 ->set(<%= prop.value.inspect %>);
00123 <% end %>
00124 <% end %>
00125
00126 <% if deployer.corba_enabled? %>
00127 RTT::corba::TaskContextServer::Create( &task_<%= task.name%> );
00128 <% end %>
00129 <% end %>
00130
00131 <% if !deployer.loggers.empty?
00132 deployer.loggers.sort_by { |filename, _| filename }.each do |filename, logger|
00133 logger.config.each do |type, reported_activity, args| %>
00134 task_<%= logger.task.name %>.connectPeers(&task_<%= reported_activity.name %>);
00135 task_<%= logger.task.name %>.report<%= type %>(<%= args.map { |v| "\"#{v}\"" }.join(", ") %>);
00136 <% end %>
00137 <% end %>
00138 <% end %>
00139
00140 Deinitializer deinit;
00141
00142
00143 <% task_activities.each do |task| %>
00144 deinit << *activity_<%= task.name%>;
00145
00146 <% if task.start?
00147 if task.context.needs_configuration? %>
00148 if (!task_<%= task.name %>.configure())
00149 {
00150 RTT::log(RTT::Error) << "cannot configure <%= task.name %>" << RTT::endlog();
00151 return -1;
00152 }
00153 <% end %>
00154 if (!task_<%= task.name %>.start())
00155 {
00156 RTT::log(RTT::Error) << "cannot start <%= task.name %>" << RTT::endlog();
00157 return -1;
00158 }
00159 <% end %>
00160 <% end %>
00161
00162 <% deployer.peers.sort_by { |a, b| [a.name, b.name] }.each do |a, b| %>
00163 task_<%= a.name %>.connectPeers(&task_<%= b.name %>);
00164 <% end %>
00165
00166 <% deployer.connections.
00167 sort_by { |src, dst, policy| [src.name, dst.name] }.
00168 each do |src, dst, policy|
00169 if src.kind_of?(TaskDeployment) %>
00170 task_<%= src.activity.name %>.connectPorts(&task_<%= dst.activity.name %>);
00171 <% else %>
00172 {
00173 <%= policy.to_code("policy") %>
00174 RTT::base::OutputPortInterface* src = dynamic_cast<RTT::base::OutputPortInterface*>(
00175 task_<%= src.activity.name %>.ports()->getPort("<%= src.name %>"));
00176 RTT::base::InputPortInterface* dst = dynamic_cast<RTT::base::InputPortInterface*>(
00177 task_<%= dst.activity.name %>.ports()->getPort("<%= dst.name %>"));
00178 src->createConnection(*dst, policy);
00179 }
00180 <% end %>
00181 <% end %>
00182
00183 <% if deployer.corba_enabled? %>
00184 struct sigaction sigint_handler;
00185 sigint_handler.sa_handler = &sigint_quit_orb;
00186 sigemptyset(&sigint_handler.sa_mask);
00187 sigint_handler.sa_flags = 0;
00188 sigint_handler.sa_restorer = 0;
00189 if (-1 == sigaction(SIGINT, &sigint_handler, 0))
00190 {
00191 std::cerr << "failed to install SIGINT handler" << std::endl;
00192 return 1;
00193 }
00194 sigset_t unblock_sigint;
00195 sigemptyset(&unblock_sigint);
00196 sigaddset(&unblock_sigint, SIGINT);
00197 if (-1 == sigprocmask(SIG_UNBLOCK, &unblock_sigint, NULL))
00198 {
00199 std::cerr << "failed to install SIGINT handler" << std::endl;
00200 return 1;
00201 }
00202 RTT::corba::TaskContextServer::RunOrb();
00203 <% elsif deployer.browse %>
00204 OCL::TaskBrowser browser(& task_<%= deployer.browse.name %>);
00205 browser.loop();
00206 <% end %>
00207
00208 return 0;
00209 }
00210