test-template.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- python -*-
3 #
4 # @file cxx_gen.py
5 # @brief rtc-template test case generator
6 # @date $Date$
7 # @author Noriaki Ando <n-ando@aist.go.jp>
8 #
9 # Copyright (C) 2008
10 # Task-intelligence Research Group,
11 # Intelligent Systems Research Institute,
12 # National Institute of
13 # Advanced Industrial Science and Technology (AIST), Japan
14 # All rights reserved.
15 #
16 # $Id$
17 #
18 
19 import yat
20 import random
21 import os
22 
23 myservice_idl = """
24 typedef sequence<string> EchoList;
25 typedef sequence<float> ValueList;
26 interface MyService
27 {
28  string echo(in string msg);
29  EchoList get_echo_history();
30  void set_value(in float value);
31  float get_value();
32  ValueList get_value_history();
33 };
34 """
35 
36 myservice_impl_h = """
37 #include "MyServiceSkel.h"
38 
39 #ifndef MYSERVICESVC_IMPL_H
40 #define MYSERVICESVC_IMPL_H
41 
42 /*
43  * Example class implementing IDL interface MyService
44  */
45 class MyServiceSVC_impl
46  : public virtual POA_MyService,
47  public virtual PortableServer::RefCountServantBase
48 {
49  private:
50  // Make sure all instances are built on the heap by making the
51  // destructor non-public
52  //virtual ~MyServiceSVC_impl();
53 
54  public:
55  // standard constructor
56  MyServiceSVC_impl();
57  virtual ~MyServiceSVC_impl();
58 
59  // attributes and operations
60  char* echo(const char* msg)
61  throw (CORBA::SystemException);
62  EchoList* get_echo_history()
63  throw (CORBA::SystemException);
64  void set_value(CORBA::Float value)
65  throw (CORBA::SystemException);
66  CORBA::Float get_value()
67  throw (CORBA::SystemException);
68  ValueList* get_value_history()
69  throw (CORBA::SystemException);
70 
71 private:
72  CORBA::Float m_value;
73  EchoList m_echoList;
74  ValueList m_valueList;
75 };
76 
77 
78 
79 #endif // MYSERVICESVC_IMPL_H
80 """
81 
82 myservice_impl_cpp = """\
83 #include "MyServiceSVC_impl.h"
84 #include <rtm/CORBA_SeqUtil.h>
85 #include <iostream>
86 
87 template <class T>
88 struct seq_print
89 {
90  seq_print() : m_cnt(0) {};
91  void operator()(T val)
92  {
93  std::cout << m_cnt << ": " << val << std::endl;
94  ++m_cnt;
95  }
96  int m_cnt;
97 };
98 
99 /*
100  * Example implementational code for IDL interface MyService
101  */
102 MyServiceSVC_impl::MyServiceSVC_impl()
103 {
104  // Please add extra constructor code here.
105 }
106 
107 
108 MyServiceSVC_impl::~MyServiceSVC_impl()
109 {
110  // Please add extra destructor code here.
111 }
112 
113 
114 /*
115  * Methods corresponding to IDL attributes and operations
116  */
117 char* MyServiceSVC_impl::echo(const char* msg)
118  throw (CORBA::SystemException)
119 {
120  CORBA_SeqUtil::push_back(m_echoList, msg);
121  std::cout << "MyService::echo() was called." << std::endl;
122  std::cout << "Message: " << msg << std::endl;
123  return CORBA::string_dup(msg);
124 }
125 
126 EchoList* MyServiceSVC_impl::get_echo_history()
127  throw (CORBA::SystemException)
128 {
129  std::cout << "MyService::get_echo_history() was called." << std::endl;
130  CORBA_SeqUtil::for_each(m_echoList, seq_print<const char*>());
131 
132  EchoList_var el;
133  el = new EchoList(m_echoList);
134  return el._retn();
135 }
136 
137 void MyServiceSVC_impl::set_value(CORBA::Float value)
138  throw (CORBA::SystemException)
139 {
140  CORBA_SeqUtil::push_back(m_valueList, value);
141  m_value = value;
142 
143  std::cout << "MyService::set_value() was called." << std::endl;
144  std::cout << "Current value: " << m_value << std::endl;
145 
146  return;
147 }
148 
149 CORBA::Float MyServiceSVC_impl::get_value()
150  throw (CORBA::SystemException)
151 {
152  std::cout << "MyService::get_value() was called." << std::endl;
153  std::cout << "Current value: " << m_value << std::endl;
154 
155  return m_value;
156 }
157 
158 ValueList* MyServiceSVC_impl::get_value_history()
159  throw (CORBA::SystemException)
160 {
161  std::cout << "MyService::get_value_history() was called." << std::endl;
162  CORBA_SeqUtil::for_each(m_valueList, seq_print<CORBA::Float>());
163 
164  ValueList_var vl;
165  vl = new ValueList(m_valueList);
166  return vl._retn();
167 }
168 """
169 
170 
171 yourservice_idl = """
172 interface YourService {
173  void func0();
174 
175  void func1(in short val);
176  void func2(inout short val);
177  void func3(out short val);
178 
179  void func4(in long val);
180  void func5(inout long val);
181  void func6(out long val);
182 
183  void func7(in float val);
184  void func8(inout float val);
185  void func9(out float val);
186 
187  void func10(in double val);
188  void func11(inout double val);
189  void func12(out double val);
190 
191 };
192 """
193 
194 vector_convert_h = """\
195 // -*- C++ -*-
196 
197 #include <istream>
198 #include <ostream>
199 #include <vector>
200 #include <string>
201 #include <coil/stringutil.h>
202 
203 template<typename T>
204 std::istream& operator>>(std::istream& is, std::vector<T>& v)
205 {
206  std::string s;
207  coil::vstring sv;
208  is >> s;
209  sv = coil::split(s ,",");
210  v.resize(sv.size());
211  for (int i(0), len(sv.size()); i < len; ++i)
212  {
213  T tv;
214  if (coil::stringTo(tv, sv[i].c_str()))
215  {
216  v[i] = tv;
217  }
218  }
219  return is;
220 }
221 """
222 
223 gen_main = """\
224 rtc-template -bcxx
225  --module-name=[name] --module-desc="Test RTC for rtc-template"
226  --module-version=1.0.0 --module-vendor=AIST --module-category=Test
227  --module-comp-type=DataFlowComponent --module-act-type=SPORADIC
228  --module-max-inst=10
229 [for ip in inports]
230  --inport="[ip.name]:[ip.type]"
231 [endfor]
232 
233 [for op in outports]
234  --outport="[op.name]:[op.type]"
235 [endfor]
236 
237 [for sp in svcports]
238  --[sp.direction]="[sp.port_name]:[sp.inst_name]:[sp.type]"
239  --[sp.direction]-idl="[sp.idl_file]"
240 [endfor]
241 
242 [for cf in configs]
243  --config="[cf.name]:[cf.type]:[cf.default]"
244 [endfor]
245 """
246 
247 rtm_config = """\
248 #!/bin/sh
249 #
250 # this is for only Linux!!
251 #
252 rtm_prefix="/usr/local"
253 rtm_exec_prefix="/usr/local"
254 rtm_cxx="g++"
255 rtm_cflags="-Wall -fPIC -O2 -I../../../../src/lib -I../../../../src/lib/rtm/idl -I../../../../src/lib/coil/include"
256 rtm_libs="-export-dynamic -luuid -ldl -L../../../../src/lib/rtm/.libs -L../../../../src/lib/coil/lib/.libs -lpthread -lomniORB4 -lomnithread -lomniDynamic4 -lRTC -lcoil"
257 rtm_libdir=""
258 rtm_version="1.0.0"
259 rtm_orb="omniORB"
260 rtm_idlc="omniidl"
261 rtm_idlflags="-bcxx -Wba -nf"
262 
263 usage()
264 {
265  cat <<EOF
266 Usage: rtm-config [OPTIONS]
267 Options:
268  [--prefix[=DIR]]
269  [--exec-prefix[=DIR]]
270  [--version]
271  [--cxx]
272  [--cflags]
273  [--libs]
274  [--libdir]
275  [--orb]
276  [--idlc]
277  [--idlflags]
278 EOF
279  exit $1
280 }
281 
282 if test $# -eq 0; then
283  usage 1 1>&2
284 fi
285 
286 
287 while test $# -gt 0; do
288  case "$1" in
289  -*=*) optarg=`echo "$1" | sed 's/[-_a-zA-Z0-9]*=//'` ;;
290  *) optarg= ;;
291  esac
292 
293  case $1 in
294  --prefix=*)
295  prefix=$optarg
296  if test $exec_prefix_set = no ; then
297  exec_prefix=$optarg
298  fi
299  ;;
300  --prefix)
301  echo_prefix=yes
302  ;;
303  --exec-prefix=*)
304  rtm_exec_prefix=$optarg
305  exec_prefix_set=yes
306  ;;
307  --exec-prefix)
308  echo_exec_prefix=yes
309  ;;
310  --version)
311  echo $rtm_version
312  ;;
313  --cxx)
314  echo_cxx=yes
315  ;;
316  --cflags)
317  echo_cflags=yes
318  ;;
319  --libs)
320  echo_libs=yes
321  ;;
322  --libdir)
323  echo_libdir=yes
324  ;;
325  --orb)
326  echo_orb=yes
327  ;;
328  --idlc)
329  echo_idlc=yes
330  ;;
331  --idlflags)
332  echo_idlflags=yes
333  ;;
334  *)
335  usage 1 1>&2
336  ;;
337  esac
338  shift
339 done
340 
341 if test "$echo_prefix" = "yes"; then
342  echo $rtm_prefix
343 fi
344 
345 if test "$echo_exec_prefix" = "yes"; then
346  echo $rtm_exec_prefix
347 fi
348 
349 if test "$echo_cxx" = "yes"; then
350  echo $rtm_cxx
351 fi
352 
353 if test "$echo_cflags" = "yes"; then
354  echo $rtm_cflags
355 fi
356 
357 if test "$echo_libs" = "yes"; then
358  echo $rtm_libs
359 fi
360 
361 if test "$echo_libdir" = "yes"; then
362  echo $rtm_libdir
363 fi
364 
365 if test "$echo_orb" = "yes"; then
366  echo $rtm_orb
367 fi
368 
369 if test "$echo_idlc" = "yes"; then
370  echo $rtm_idlc
371 fi
372 
373 if test "$echo_idlflags" = "yes"; then
374  echo $rtm_idlflags
375 fi
376 
377 """
378 
379 bat_header = """\
380 @set PATH="%RTM_ROOT%\\utils\\rtc-template";%PATH%
381 @set PYTHONPATH="%RTM_ROOT%\\utils\\rtc-template"
382 
383 del /F /Q *.cpp *.h *.hh *.cc *.sln *.vcproj *.vsprops *.yaml
384 del /F /Q copyprops.bat Makefile.* README.*
385 
386 rmdir /Q /S [name]
387 
388 rmdir /Q /S [name]Comp
389 
390 """
391 
392 sh_header = """\
393 #!/bin/sh
394 export PYTHONPATH=../../:../../py_helper
395 export RTM_ROOT=../../../../
396 export PATH=./:../../:../../../rtm-skelwrapper:$PATH
397 
398 rm -rf *.cpp *.h *.hh *.cc *.sln *.vcproj *.vsprops *.yaml
399 rm -rf copyprops.bat Makefile.* README.*
400 rm -rf [name] [name]Comp
401 
402 """
403 
404 bat_footer = """
405 
406 call copyprops.bat
407 for %%x in (*.tmp) do copy /y %%x %%~nx
408 
409 echo #include "VectorConvert.h" >> [name].h
410 
411 """
412 
413 sh_footer = """
414 
415 for tmpname in *.tmp
416 do
417  fname=`basename $tmpname .tmp`
418  cp -f $tmpname $fname
419 done
420 
421 echo '#include "VectorConvert.h"' >> [name].h
422 
423 make -f Makefile.*
424 """
425 
426 build_vc8_bat = """\
427 @set PATH="C:\\Program Files\\Microsoft Visual Studio 8\\VC\\vcpackages";%PATH%
428 
429 [for proj in projects]
430 cd [proj]
431 call gen.bat
432 vcbuild [proj]_vc8.sln
433 cd ..
434 [endfor]
435 """
436 
437 build_vc9_bat = """\
438 @set PATH="C:\\Program Files\\Microsoft Visual Studio 9.0\\VC\\vcpackages";%PATH%
439 
440 [for proj in projects]
441 cd [proj]
442 call gen.bat
443 vcbuild [proj]_vc9.sln
444 cd ..
445 [endfor]
446 """
447 
448 build_sh = """\
449 #!/bin/sh
450 
451 [for proj in projects]
452 cd [proj]
453 sh gen.sh
454 #make -f Makefile.[proj]
455 if test -f [proj]Comp; then
456  echo [proj]: OK >> ../build_status
457 else
458  echo [proj]: NG >> ../build_status
459 fi
460 cd ..
461 [endfor]
462 """
463 
464 inports = [
465  {"name": "in00", "type": "TimedShort"},
466  {"name": "in01", "type": "TimedLong"},
467  {"name": "in02", "type": "TimedUShort"},
468  {"name": "in03", "type": "TimedULong"},
469  {"name": "in04", "type": "TimedFloat"},
470  {"name": "in05", "type": "TimedDouble"},
471  {"name": "in06", "type": "TimedChar"},
472  {"name": "in07", "type": "TimedBoolean"},
473  {"name": "in08", "type": "TimedOctet"},
474  {"name": "in09", "type": "TimedString"},
475  {"name": "in10", "type": "TimedShortSeq"},
476  {"name": "in11", "type": "TimedLongSeq"},
477  {"name": "in12", "type": "TimedUShortSeq"},
478  {"name": "in13", "type": "TimedULongSeq"},
479  {"name": "in14", "type": "TimedFloatSeq"},
480  {"name": "in15", "type": "TimedDoubleSeq"},
481  {"name": "in16", "type": "TimedCharSeq"},
482  {"name": "in17", "type": "TimedBooleanSeq"},
483  {"name": "in18", "type": "TimedOctetSeq"},
484  {"name": "in19", "type": "TimedStringSeq"}
485  ]
486 
487 outports = [
488  {"name": "out00", "type": "TimedShort"},
489  {"name": "out01", "type": "TimedLong"},
490  {"name": "out02", "type": "TimedUShort"},
491  {"name": "out03", "type": "TimedULong"},
492  {"name": "out04", "type": "TimedFloat"},
493  {"name": "out05", "type": "TimedDouble"},
494  {"name": "out06", "type": "TimedChar"},
495  {"name": "out07", "type": "TimedBoolean"},
496  {"name": "out08", "type": "TimedOctet"},
497  {"name": "out09", "type": "TimedString"},
498  {"name": "out10", "type": "TimedShortSeq"},
499  {"name": "out11", "type": "TimedLongSeq"},
500  {"name": "out12", "type": "TimedUShortSeq"},
501  {"name": "out13", "type": "TimedULongSeq"},
502  {"name": "out14", "type": "TimedFloatSeq"},
503  {"name": "out15", "type": "TimedDoubleSeq"},
504  {"name": "out16", "type": "TimedCharSeq"},
505  {"name": "out17", "type": "TimedBooleanSeq"},
506  {"name": "out18", "type": "TimedOctetSeq"},
507  {"name": "out19", "type": "TimedStringSeq"}
508  ]
509 
510 configs = [
511  {"name": "conf_short", "type": "short",
512  "default": "12"},
513  {"name": "conf_int", "type": "int",
514  "default": "1234"},
515  {"name": "conf_long", "type": "long",
516  "default": "-12345"},
517  {"name": "conf_ushort", "type": "unsigned short",
518  "default": "987"},
519  {"name": "conf_uint", "type": "unsigned int",
520  "default": "9876"},
521  {"name": "conf_ulong", "type": "unsigned long",
522  "default": "98765"},
523  {"name": "conf_float", "type": "float",
524  "default": "3.14159265"},
525  {"name": "conf_double", "type": "double",
526  "default": "0.0000000001"},
527  {"name": "conf_string", "type": "std::string",
528  "default": "OpenRTM-aist"},
529  {"name": "conf_vshort", "type": "std::vector<short>",
530  "default": "0,1,2,3,4,5,6,7,8,9"},
531  {"name": "conf_vint", "type": "std::vector<int>",
532  "default": "9,8,7,6,5,4,3,2,1,0"},
533  {"name": "conf_vlong", "type": "std::vector<long>",
534  "default": "0,10,20,30,40,50,60,70,80,90"},
535  {"name": "conf_vushort", "type": "std::vector<unsigned short>",
536  "default": "1,2"},
537  {"name": "conf_vuint", "type": "std::vector<unsigned int>",
538  "default": "0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20"},
539  {"name": "conf_vulong", "type": "std::vector<unsigned long>",
540  "default": "0,10000,20000,30000,40000,50000,60000,70000,80000,90000"},
541  {"name": "conf_vfloat", "type": "std::vector<float>",
542  "default": "0.1,0.01,0.001,0.0001,0.00001,0.000001,0.0000001,0.00000001"},
543  {"name": "conf_vdouble", "type": "std::vector<double>",
544  "default": "1.1,1.01,1.001,1.0001,1.00001,1.000001,1.0000001,1.00000001"}
545 ]
546 
547 svcports = [
548  {"type": "MyService", "direction": "service",
549  "port_name": "sp0", "inst_name": "my0",
550  "idl_file": "MyService.idl", "idl_data": myservice_idl,
551  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
552  {"type": "MyService", "direction": "consumer",
553  "port_name": "sp0", "inst_name": "my1",
554  "idl_file": "MyService.idl", "idl_data": myservice_idl,
555  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
556  {"type": "MyService", "direction": "service",
557  "port_name": "sp1", "inst_name": "my2",
558  "idl_file": "MyService.idl", "idl_data": myservice_idl,
559  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
560  {"type": "MyService", "direction": "consumer",
561  "port_name": "sp1", "inst_name": "my3",
562  "idl_file": "MyService.idl", "idl_data": myservice_idl,
563  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
564  {"type": "MyService", "direction": "service",
565  "port_name": "sp2", "inst_name": "my4",
566  "idl_file": "MyService.idl", "idl_data": myservice_idl,
567  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
568  {"type": "MyService", "direction": "consumer",
569  "port_name": "sp2", "inst_name": "my5",
570  "idl_file": "MyService.idl", "idl_data": myservice_idl,
571  "impl_h": myservice_impl_h, "impl_cpp": myservice_impl_cpp},
572  {"type": "YourService", "direction": "service",
573  "port_name": "sp0", "inst_name": "your0",
574  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
575  "impl_h": None, "impl_cpp": None},
576  {"type": "YourService", "direction": "consumer",
577  "port_name": "sp0", "inst_name": "your1",
578  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
579  "impl_h": None, "impl_cpp": None},
580  {"type": "YourService", "direction": "service",
581  "port_name": "sp1", "inst_name": "your2",
582  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
583  "impl_h": None, "impl_cpp": None},
584  {"type": "YourService", "direction": "consumer",
585  "port_name": "sp1", "inst_name": "your3",
586  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
587  "impl_h": None, "impl_cpp": None},
588  {"type": "YourService", "direction": "service",
589  "port_name": "sp2", "inst_name": "your4",
590  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
591  "impl_h": None, "impl_cpp": None},
592  {"type": "YourService", "direction": "consumer",
593  "port_name": "sp2", "inst_name": "your5",
594  "idl_file": "YourService.idl", "idl_data": yourservice_idl,
595  "impl_h": None, "impl_cpp": None}
596  ]
597 
598 
599 nums = [0, 1, 2, 10]
600 
601 params = {
602  "inports": inports,
603  "outports": outports,
604  "svcports": svcports,
605  "configs": configs
606  }
607 
608 def _mkdir(newdir):
609  """works the way a good mkdir should :)
610  - already exists, silently complete
611  - regular file in the way, raise an exception
612  - parent directory(ies) does not exist, make them as well
613  """
614  if os.path.isdir(newdir):
615  pass
616  elif os.path.isfile(newdir):
617  raise OSError("a file with the same name as the desired " \
618  "dir, '%s', already exists." % newdir)
619  else:
620  head, tail = os.path.split(newdir)
621  if head and not os.path.isdir(head):
622  _mkdir(head)
623  #print "_mkdir %s" % repr(newdir)
624  if tail:
625  os.mkdir(newdir)
626 
627 class TestGen:
628  def __init__(self, ip_num, op_num, sp_num, cf_num):
629  self.ip_num = ip_num
630  self.op_num = op_num
631  self.sp_num = sp_num
632  self.cf_num = cf_num
633  for key in params.keys():
634  random.shuffle(params[key])
635  self.params = params
636  self.pjnames = []
637 
638  def generate(self):
639  self.gen()
640  self.craete_build_sh()
641 
642  def craete_build_sh(self):
643  dict = {}
644  dict["projects"] = self.pjnames
645  builds = {"build.sh": build_sh,
646  "build_vc8.bat": build_vc8_bat,
647  "build_vc9.bat": build_vc9_bat
648  }
649  for key in builds.keys():
650  fd = open(key, "w")
651  fd.write(yat.Template(builds[key]).generate(dict))
652  fd.close()
653  os.chmod(key, 0755)
654 
655 
656  def mkdir(self, dirname):
657  _mkdir(dirname)
658 
659  def dict(self, ip, op, sp, cf):
660  name = "Sample_%d_%d_%d_%d" % (ip, op, sp, cf)
661  dict = {"name": name}
662  p = ["inports", "outports", "svcports", "configs"]
663  n = [ip, op, sp, cf]
664  for i in range(len(n)):
665  dict[p[i]] = self.params[p[i]][0:n[i]]
666  return dict
667 
668  def create_gen_sh(self, dict):
669  fname = dict["name"] + "/gen.sh"
670  fd = open(fname, "w")
671  head = yat.Template(sh_header).generate(dict)
672  body = yat.Template(gen_main).generate(dict)
673  body = self.add_cmark(body, "\\")
674  foot = yat.Template(sh_footer).generate(dict)
675 
676  sh_all = head + body + foot
677  fd.write(sh_all)
678  fd.close()
679  os.chmod(fname, 0755)
680 
681  def create_gen_bat(self, dict):
682  fname = dict["name"] + "/gen.bat"
683  fd = open(fname, "w")
684  head = yat.Template(bat_header).generate(dict)
685  body = yat.Template(gen_main).generate(dict)
686  body = body.replace("rtc-template", "rtc-template.py")
687  body = self.add_cmark(body, "^")
688  foot = yat.Template(bat_footer).generate(dict)
689 
690  bat_all = head + body + foot
691  bat_all.replace("\r\n", "\n").replace("\n", "\r\n")
692  fd.write(bat_all)
693  fd.close()
694  os.chmod(fname, 0755)
695 
696  def add_cmark(self, text, mark):
697  lines = [t for t in text.split("\n") if t != ""]
698  return (mark + "\n").join(lines)
699 
700  def create_idl(self, dict):
701  idls = []
702  for svc in dict["svcports"]:
703  if not svc["idl_file"] in idls:
704  fname = dict["name"] + "/" + svc["idl_file"]
705  fd = open(fname, "w")
706  fd.write(svc["idl_data"])
707  fd.close()
708  idls.append(svc["idl_file"])
709 
710  if svc["impl_h"] != None:
711  cpp_fname = dict["name"] + "/" + \
712  svc["idl_file"].replace(".idl","SVC_impl.cpp.tmp")
713  fd = open(cpp_fname, "w")
714  fd.write(svc["impl_cpp"])
715  fd.close
716 
717  h_fname = dict["name"] + "/" + \
718  svc["idl_file"].replace(".idl","SVC_impl.h.tmp")
719  fd = open(h_fname, "w")
720  fd.write(svc["impl_h"])
721  fd.close
722 
723  def create_vecconv(self, dict):
724  fname = dict["name"] + "/" + "VectorConvert.h.tmp"
725  fd = open(fname, "w")
726  fd.write(vector_convert_h)
727  fd.close()
728 
729  def create_rtmconfig(self, dict):
730  fname = dict["name"] + "/rtm-config"
731  fd = open(fname, "w")
732  fd.write(rtm_config)
733  fd.close()
734  os.chmod(fname, 0755)
735 
736  def create_gen(self, dict):
737  self.create_gen_sh(dict)
738  self.create_gen_bat(dict)
739  self.create_idl(dict)
740  self.create_vecconv(dict)
741  self.create_rtmconfig(dict)
742 
743  def gen(self):
744  for ip in self.ip_num:
745  for op in self.op_num:
746  for sp in self.sp_num:
747  for cf in self.cf_num:
748  dict = self.dict(ip, op, sp, cf)
749  self.mkdir(dict["name"])
750  self.create_gen(dict)
751  self.pjnames.append(dict["name"])
752 
753 
754 if __name__ == "__main__":
755  t = TestGen([0,1,5],[0,1,5],[0,1,5],[0,1,5])
756 # t = TestGen([5],[5],[5],[5])
757  t.generate()
def create_gen_bat(self, dict)
def create_gen_sh(self, dict)
def __init__(self, ip_num, op_num, sp_num, cf_num)
def add_cmark(self, text, mark)
def _mkdir(newdir)
def create_gen(self, dict)
def create_idl(self, dict)
def mkdir(self, dirname)
def create_rtmconfig(self, dict)
def create_vecconv(self, dict)
def dict(self, ip, op, sp, cf)


openrtm_aist
Author(s): Noriaki Ando
autogenerated on Mon Jun 10 2019 14:07:56