Class: Orocos::Process

Inherits:
ProcessBase show all
Defined in:
lib/orocos/process.rb

Overview

The representation of an Orocos process. It manages starting the process and cleaning up when the process dies.

Constant Summary collapse

VALID_LOG_LEVELS =
[:debug, :info, :warn, :error, :fatal, :disable]
SIGNAL_NUMBERS =
{
    'SIGABRT' => 1,
    'SIGINT' => 2,
    'SIGKILL' => 9,
    'SIGSEGV' => 11
}
@@logfile_indexes =
Hash.new
@@gdb_port =
30000

Class Attribute Summary collapse

Instance Attribute Summary collapse

Attributes inherited from ProcessBase

#default_logger, #logged_ports, #model, #name, #name_mappings, #tasks

Class Method Summary collapse

Instance Method Summary collapse

Methods inherited from ProcessBase

#default_logger_name, #each_task, #get_mapped_name, #log_all_ports, #map_name, #orogen, #register_task, resolve_prefix, #setup_default_logger, #task, #task_names

Constructor Details

#initialize(name, model_name = name) ⇒ Process

Creates a new Process instance which will be able to start and supervise the execution of the given Orocos component

deprecated form


428
429
430
431
432
433
434
435
# File 'lib/orocos/process.rb', line 428

def initialize(name, model = name, loader: Orocos.default_pkgconfig_loader)
    model = if model.respond_to?(:to_str)
                loader.deployment_model_from_name(model)
            else model
            end
    @pkg = loader.available_deployments[model.name]
    super(name, model)
end

Class Attribute Details

.registered_processes{Integer=>Process}

A map of existing running processes


368
369
370
# File 'lib/orocos/process.rb', line 368

def registered_processes
  @registered_processes
end

Instance Attribute Details

#pidObject (readonly)

The component process ID


351
352
353
# File 'lib/orocos/process.rb', line 351

def pid
  @pid
end

#pkgObject (readonly)

The component PkgConfig instance


349
350
351
# File 'lib/orocos/process.rb', line 349

def pkg
  @pkg
end

Class Method Details

.allocate_gdb_portObject


857
858
859
# File 'lib/orocos/process.rb', line 857

def self.allocate_gdb_port
    @@gdb_port += 1
end

.deregister(pid) ⇒ Object

Deregisters a process object that was registered with register


390
391
392
393
394
395
# File 'lib/orocos/process.rb', line 390

def self.deregister(pid)
    if process = registered_processes.delete(pid)
        process
    else raise ArgumentError, "no process registered for PID #{pid}"
    end
end

.each {|process| ... } ⇒ Object

Enumerates all registered processes

Yield Parameters:

  • process (Process)

    the process object


400
401
402
# File 'lib/orocos/process.rb', line 400

def self.each(&block)
    registered_processes.each_value(&block)
end

.from_pid(pid) ⇒ nil, Process

Returns the process that has the given PID


357
358
359
360
361
# File 'lib/orocos/process.rb', line 357

def self.from_pid(pid)
    if result = registered_processes[pid]
               return result
           end
end

.gdb_base_port=(port) ⇒ Object


852
853
854
# File 'lib/orocos/process.rb', line 852

def self.gdb_base_port=(port)
    @@gdb_port = port - 1
end

.kill(processes, wait = true) ⇒ Object

Kills the given processes


845
846
847
848
849
850
# File 'lib/orocos/process.rb', line 845

def self.kill(processes, wait = true)
    processes.each { |p| p.kill if p.running? }
    if wait
        processes.each { |p| p.join }
    end
end

.normalize_wait_option(wait, valgrind, gdb) ⇒ Object

This method is part of a private API. You should avoid using this method if possible, as it may be removed or be changed in the future.

Apply default parameters for the wait option in Orocos.run and #spawn


567
568
569
570
571
572
573
574
575
576
577
578
# File 'lib/orocos/process.rb', line 567

def self.normalize_wait_option(wait, valgrind, gdb)
    if wait.nil?
        wait =
            if valgrind then 600
            elsif gdb then 600
            else 20
            end
    elsif !wait
        false
    else wait
    end
end

.parse_cmdline_wrapper_option(cmd, enable, cmd_options, deployments) ⇒ Object .parse_cmdline_wrapper_option(cmd, deployments, cmd_options, all_deployments) ⇒ Object .parse_cmdline_wrapper_option(cmd, deployments_to_cmd_options, cmd_options, all_deployments) ⇒ Object

This method is part of a private API. You should avoid using this method if possible, as it may be removed or be changed in the future.

Normalizes the options for command line wrappers such as gdb and valgrind as passed to Orocos.run


717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
# File 'lib/orocos/process.rb', line 717

def self.parse_cmdline_wrapper_option(cmd, deployments, options, all_deployments)
    if !deployments
        return Hash.new
    end

    if !system("which #{cmd} > /dev/null 2>&1")
        raise "'#{cmd}' option is specified, but #{cmd} seems not to be installed"
    end

    if !deployments.respond_to?(:to_hash)
        if deployments.respond_to?(:to_str)
            deployments = [deployments]
        elsif !deployments.respond_to?(:to_ary)
            deployments = all_deployments
        end

        deployments = deployments.inject(Hash.new) { |h, name| h[name] = options; h }
    end
    deployments.each_key do |name|
        if !all_deployments.include?(name)
            raise ArgumentError, "#{name}, selected to be executed under #{cmd}, is not a known deployment/model"
        end
    end
end

.parse_log_level_option(options, all_deployments) ⇒ Hash<String,Symbol>

This method is part of a private API. You should avoid using this method if possible, as it may be removed or be changed in the future.

Normalizes the log_level option passed to Orocos.run.

level that should be applied to all deployments. Otherwise, it is a hash from a process name to the log level that should be applied for this particular deployment


682
683
684
685
686
687
688
# File 'lib/orocos/process.rb', line 682

def self.parse_log_level_option( options, all_deployments )
    if !options.respond_to?(:to_hash)
        all_deployments.inject(Hash.new) { |h, name| h[name] = options; h }
    else
        options
    end
end

.parse_run_options(*names, wait: nil, loader: Orocos.default_loader, valgrind: false, valgrind_options: Hash.new, gdb: false, gdb_options: Hash.new, log_level: nil, output: nil, oro_logfile: "orocos.%m-%p.txt", working_directory: Orocos.default_working_directory, cmdline_args: Hash.new) ⇒ (Array<String,Hash,String,Hash>,Object)

This method is part of a private API. You should avoid using this method if possible, as it may be removed or be changed in the future.

Separate the list of deployments from the spawn options in options passed to Orocos.run

Valid options are:


634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
# File 'lib/orocos/process.rb', line 634

def self.parse_run_options(*names, wait: nil, loader: Orocos.default_loader,
                           valgrind: false, valgrind_options: Hash.new,
                           gdb: false, gdb_options: Hash.new,
                           log_level: nil,
                           output: nil, oro_logfile:  "orocos.%m-%p.txt",
                           working_directory: Orocos.default_working_directory,
                           cmdline_args: Hash.new)
    deployments, models = partition_run_options(*names, loader: loader)
    wait = normalize_wait_option(wait, valgrind, gdb)

    all_deployments = deployments.keys.map(&:name) + models.values.flatten
    valgrind = parse_cmdline_wrapper_option(
        'valgrind', valgrind, valgrind_options, all_deployments)
    gdb = parse_cmdline_wrapper_option(
        'gdbserver', gdb, gdb_options, all_deployments)
    log_level = parse_log_level_option(log_level, all_deployments)

    name_mappings = resolve_name_mappings(deployments, models)
    processes = name_mappings.map do |deployment_name, mappings, name|
        output = if output
                     output.gsub '%m', name
                 end

        spawn_options = Hash[
            working_directory: working_directory,
            output: output,
            valgrind: valgrind[name],
            gdb: gdb[name],
            cmdline_args: cmdline_args,
            wait: false,
            log_level: log_level[name],
            oro_logfile: oro_logfile]
        [deployment_name, mappings, name, spawn_options]
    end
    return processes, wait
end

.partition_run_options(*names, loader: Orocos.default_loader) ⇒ Object

Orocos.run 'xsens_imu::Task' => ['imu1', 'imu2']


525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
# File 'lib/orocos/process.rb', line 525

def self.partition_run_options(*names, loader: Orocos.default_loader)
    mapped_names = Hash.new
    if names.last.kind_of?(Hash)
        mapped_names = names.pop
    end

    deployments, models = Hash.new, Hash.new
    names.each { |n| mapped_names[n] = nil }
    mapped_names.each do |object, new_name|
        # If given a name, resolve to the corresponding oroGen spec
        # object
        if object.respond_to?(:to_str) || object.respond_to?(:to_sym)
            object = object.to_s
            begin
                object = loader.task_model_from_name(object)
            rescue OroGen::NotFound
                begin
                    object = loader.deployment_model_from_name(object)
                rescue OroGen::NotFound
                    raise ArgumentError, "#{object} is neither a task model nor a deployment name"
                end
            end
        end

        case object
        when OroGen::Spec::TaskContext
            if !new_name
                raise ArgumentError, "you must provide a task name when starting a component by type, as e.g. Orocos.run 'xsens_imu::Task' => 'xsens'"
            end
            models[object] = Array(new_name)
        when OroGen::Spec::Deployment
            deployments[object] = (new_name if new_name)
        else raise ArgumentError, "expected a task context model or a deployment model, got #{object}"
        end
    end
    return deployments, models
end

.register(process) ⇒ void

This method returns an undefined value.

Registers a PID-to-process mapping.

This can be called only for running processes

See Also:


379
380
381
382
383
384
385
# File 'lib/orocos/process.rb', line 379

def self.register(process)
    if !process.alive?
        raise ArgumentError, "cannot register a non-running process"
    end
    registered_processes[process.pid] = process
    nil
end

.resolve_name_mappings(deployments, models) ⇒ Array<(String,Hash,String)>

This method is part of a private API. You should avoid using this method if possible, as it may be removed or be changed in the future.

Resolve the 'prefix' options given to Orocos.run into an exhaustive task name mapping


756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
# File 'lib/orocos/process.rb', line 756

def self.resolve_name_mappings(deployments, models)
    processes = []
    processes += deployments.map do |deployment, prefix|
        mapped_name   = deployment.name
        name_mappings = Hash.new
        if prefix
            name_mappings = ProcessBase.resolve_prefix(deployment, prefix)
            mapped_name = "#{prefix}#{deployment.name}"
        end

        [deployment.name, name_mappings, mapped_name]
    end
    models.each do |model, desired_names|
        desired_names = [desired_names] unless desired_names.kind_of? Array 
        desired_names.each do |desired_name|
            process_name = OroGen::Spec::Project.default_deployment_name(model.name)
            name_mappings = Hash[
                process_name => desired_name,
                "#{process_name}_Logger" => "#{desired_name}_Logger"]

            processes << [process_name, name_mappings, desired_name]
        end
    end
    processes
end

.run(*args, **options) ⇒ Object

Deprecated.

use Orocos.run directly instead


783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
# File 'lib/orocos/process.rb', line 783

def self.run(*args, **options)
    if !Orocos.initialized?
        #try to initialize orocos before bothering the user
        Orocos.initialize
    end
    if !Orocos::CORBA.initialized?
        raise "CORBA layer is not initialized! There might be problem with the installation."
    end

    begin
        process_specs, wait = parse_run_options(*args, **options)

        # Then spawn them, but without waiting for them
        processes = process_specs.map do |deployment_name, name_mappings, name, spawn_options|
            p = Process.new(name, deployment_name)
            name_mappings.each do |old, new|
                p.map_name old, new
            end
            p.spawn(spawn_options)
            p
        end

        # Finally, if the user required it, wait for the processes to run
        if wait
            timeout = if wait.kind_of?(Numeric)
                          wait
                      else Float::INFINITY
                      end
            processes.each { |p| p.wait_running(timeout) }
        end

    rescue Exception => original_error
        # Kill the processes that are already running
        if processes
            begin
                kill(processes.map { |p| p if p.running? }.compact)
            rescue Exception => e
                Orocos.warn "failed to kill the started processes, you will have to kill them yourself"
                Orocos.warn e.message
                e.backtrace.each do |l|
                    Orocos.warn "  #{l}"
                end
                raise original_error
            end
        end
        raise
    end

    if block_given?
        Orocos.guard(*processes) do
            yield(*processes)
        end
    else
        processes
    end
end

.try_task_cleanup(task) ⇒ Object

Tries to stop and cleanup the provided task. Returns true if it was successful, and false otherwise


1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
# File 'lib/orocos/process.rb', line 1143

def self.try_task_cleanup(task)
    begin
        task.stop(false)
        if task.model && task.model.needs_configuration?
            task.cleanup(false)
        end
    rescue StateTransitionFailed
    end

    task.each_port do |port|
        port.disconnect_all
    end

    true

rescue Exception => e
    Orocos.warn "clean shutdown of #{task.name} failed: #{e.message}"
    e.backtrace.each do |line|
        Orocos.warn line
    end
    false
end

.wait_running(process, timeout = nil, name_service = Orocos::CORBA.name_service, &block) ⇒ Object

Wait for a process to become reachable


1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
# File 'lib/orocos/process.rb', line 1071

def self.wait_running(process, timeout = nil, name_service = Orocos::CORBA.name_service, &block)
    if timeout == 0
	return nil if !process.alive?

               # Use custom block to check if the process is reachable
               if block_given?
                   block.call(process)
               else
                   # Get any task name from that specific deployment, and check we
                   # can access it. If there is none
                   all_reachable = process.task_names.all? do |task_name|
                       if name_service.task_reachable?(task_name)
                           Orocos.debug "#{task_name} is reachable"
                           true
                       else
                           Orocos.debug "could not access #{task_name}, #{name} is not running yet ..."
                           false
                       end
                   end
                   if all_reachable
                       Orocos.info "all tasks of #{process.name} are reachable, assuming it is up and running"
                   end
                   all_reachable
               end
    else
               start_time = Time.now
               got_alive = process.alive?
               while true
	    if wait_running(process, 0, name_service, &block)
		break
                   elsif not timeout
                       break
                   elsif timeout < Time.now - start_time
                       break
                   end

                   if got_alive && !process.alive?
                       raise Orocos::NotFound, "#{process.name} was started but crashed"
                   end
                   sleep 0.1
               end

               if process.alive?
                   return true
               else
                   raise Orocos::NotFound, "cannot get a running #{process.name} module"
               end
    end
end

Instance Method Details

#alive?Boolean

True if the process is running


453
# File 'lib/orocos/process.rb', line 453

def alive?; !!@pid end

#dead!(exit_status) ⇒ Object

Called externally to announce a component dead.


458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
# File 'lib/orocos/process.rb', line 458

def dead!(exit_status) # :nodoc:
           exit_status = (@exit_status ||= exit_status)
           if !exit_status
               Orocos.info "deployment #{name} exited, exit status unknown"
           elsif exit_status.success?
               Orocos.info "deployment #{name} exited normally"
           elsif exit_status.signaled?
               if @expected_exit == exit_status.termsig
                   Orocos.info "deployment #{name} terminated with signal #{exit_status.termsig}"
               elsif @expected_exit
                   Orocos.info "deployment #{name} terminated with signal #{exit_status.termsig} but #{@expected_exit} was expected"
               else
                   Orocos.error "deployment #{name} unexpectedly terminated with signal #{exit_status.termsig}"
                   Orocos.error "This is normally a fault inside the component, not caused by the framework."
                   Orocos.error "Try to run your component within gdb or valgrind with"
                   Orocos.error "  Orocos.run 'component', :gdb=>true"
                   Orocos.error "  Orocos.run 'component', :valgrind=>true"
                   Orocos.error "Make also sure that your component is installed by running 'amake' in it"
               end
           else
               Orocos.warn "deployment #{name} terminated with code #{exit_status.to_i}"
           end

           pid, @pid = @pid, nil
           Process.deregister(pid)

           # Force unregistering the task contexts from CORBA naming
           # service
           # task_names.each do |name|
           #     puts "deregistering #{name}"
           #     Orocos::CORBA.unregister(name)
           # end
end

#host_idObject

A string describing the host. It can be used to check if two processes are running on the same host


406
407
408
# File 'lib/orocos/process.rb', line 406

def host_id
    'localhost'
end

#joinObject

Waits until the process dies

This is valid only if the module has been started under Orocos supervision, using #spawn


441
442
443
444
445
446
447
448
449
450
# File 'lib/orocos/process.rb', line 441

def join
    return unless alive?

	    begin
		::Process.waitpid(pid)
        exit_status = $?
        dead!(exit_status)
	    rescue Errno::ECHILD
	    end
end

#kill(wait = true, signal = nil) ⇒ Object

Kills the process either cleanly by requesting a shutdown if signal == nil, or forcefully by using UNIX signals if signal is a signal name.


1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
# File 'lib/orocos/process.rb', line 1168

def kill(wait = true, signal = nil)
    tpid = pid
    return if !tpid # already dead

    # Stop all tasks and disconnect the ports
    if !signal
        clean_shutdown = true
        begin
            each_task do |task|
                if !self.class.try_task_cleanup(task)
                    clean_shutdown = false
                    break
                end
            end
        rescue Orocos::NotFound, Orocos::NoModel
            # We're probably still starting the process. Just go on and
            # signal it
            clean_shutdown = false
        end
        if !clean_shutdown
            Orocos.warn "clean shutdown of process #{name} failed"
        end
    end

    expected_exit = nil
    if clean_shutdown
        expected_exit = signal = SIGNAL_NUMBERS['SIGINT']
	    else
        signal = SIGNAL_NUMBERS['SIGINT']
    end

    if signal 
        if !expected_exit
            Orocos.warn "sending #{signal} to #{name}"
        end

        if signal.respond_to?(:to_str) && signal !~ /^SIG/
            signal = "SIG#{signal}"
        end

        expected_exit ||=
            if signal.kind_of?(Integer) then signal
            else SIGNAL_NUMBERS[signal] || signal
            end

        @expected_exit = expected_exit
        begin
            ::Process.kill(signal, tpid)
        rescue Errno::ESRCH
            # Already exited
            return
        end
    end

    if wait
        join
        if @exit_status && @exit_status.signaled?
            if !expected_exit
                Orocos.warn "#{name} unexpectedly exited with signal #{@exit_status.termsig}"
            elsif @exit_status.termsig != expected_exit
                Orocos.warn "#{name} was expected to quit with signal #{expected_exit} but terminated with signal #{@exit_status.termsig}"
            end
        end
    end
end

#on_localhost?Boolean

Returns true if the process is located on the same host than the Ruby interpreter


412
413
414
# File 'lib/orocos/process.rb', line 412

def on_localhost?
    host_id == 'localhost'
end

#running?Boolean

True if the process is running


455
# File 'lib/orocos/process.rb', line 455

def running?; alive? end

#spawn(log_level: nil, working_directory: Orocos.default_working_directory, cmdline_args: Hash.new, oro_logfile: "orocos.%m-%p.txt", prefix: nil, tracing: Orocos.tracing?, name_service: Orocos::CORBA.name_service, wait: nil, output: nil, gdb: nil, valgrind: nil) ⇒ Object

Spawns this process


894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
# File 'lib/orocos/process.rb', line 894

def spawn(log_level: nil, working_directory: Orocos.default_working_directory,
          cmdline_args: Hash.new,
          oro_logfile:  "orocos.%m-%p.txt",
          prefix: nil, tracing: Orocos.tracing?, name_service: Orocos::CORBA.name_service,
          wait: nil,
          output: nil,
          gdb: nil, valgrind: nil)

	    raise "#{name} is already running" if alive?
	    Orocos.info "starting deployment #{name}"

    # Setup mapping for prefixed tasks in Process class
    prefix_mappings = ProcessBase.resolve_prefix(model, prefix)
    name_mappings = prefix_mappings.merge(self.name_mappings)
    self.name_mappings = name_mappings

    # If possible, check that we won't clash with an already running
    # process
    task_names.each do |name|
        if name_service.task_reachable?(name)
            raise ArgumentError, "there is already a running task called #{name}, are you starting the same component twice ?"
        end
    end

    if wait.nil?
        wait =
            if valgrind then 600
            elsif gdb then 600
            else 20
            end
    end

    cmdline_args = cmdline_args.dup
    cmdline_args[:rename] ||= []
    name_mappings.each do |old, new|
        cmdline_args[:rename].push "#{old}:#{new}"
    end

    if valgrind
        cmdline_wrapper = 'valgrind'
        cmdline_wrapper_options =
            if valgrind.respond_to?(:to_ary)
                valgrind
            else []
            end
    elsif gdb
        cmdline_wrapper = 'gdbserver'
        cmdline_wrapper_options =
            if gdb.respond_to?(:to_ary)
                gdb
            else []
            end
        gdb_port = Process.allocate_gdb_port
        cmdline_wrapper_options << "localhost:#{gdb_port}"
    end

	    if !name_service.ip.empty?
		ENV['ORBInitRef'] = "NameService=corbaname::#{name_service.ip}"
	    end

    module_bin = pkg.binfile
    if !module_bin # assume an older orogen version
        module_bin = "#{pkg.exec_prefix}/bin/#{name}"
    end
    cmdline = [module_bin]

    # check arguments for log_level
    if log_level
        valid_levels = [:debug, :info, :warn, :error, :fatal, :disable]
        if valid_levels.include?(log_level)
            log_level = log_level.to_s.upcase
        else
            raise ArgumentError, "'#{log_level}' is not a valid log level." +
                " Valid options are #{valid_levels}."
        end
    end
		    
	    read, write = IO.pipe
	    @pid = fork do 
        if tracing
            ENV['LD_PRELOAD'] = Orocos.tracing_library_path
        end

        pid = ::Process.pid
        real_name = get_mapped_name(name)

        ENV['BASE_LOG_LEVEL'] = log_level if log_level

		if output && output.respond_to?(:to_str)
		    output_file_name = output.
			gsub('%m', real_name).
			gsub('%p', pid.to_s)
            if working_directory
                output_file_name = File.expand_path(output_file_name, working_directory)
            end

            output = File.open(output_file_name, 'a')
		end

        if oro_logfile
            oro_logfile = oro_logfile.
                gsub('%m', real_name).
                gsub('%p', pid.to_s)
            if working_directory
                oro_logfile = File.expand_path(oro_logfile, working_directory)
            end
            ENV['ORO_LOGFILE'] = oro_logfile
        else
            ENV['ORO_LOGFILE'] = "/dev/null"
        end

		if output
		    STDERR.reopen(output)
		    STDOUT.reopen(output)
		end

        if output_file_name && valgrind
            cmdline.unshift "--log-file=#{output_file_name}.valgrind"
        end

        if cmdline_wrapper
            cmdline = cmdline_wrapper_options + cmdline
            cmdline.unshift cmdline_wrapper
        end
        
        # Command line arguments have to be of type --<option>=<value>
        # or if <value> is nil a valueless option, i.e. --<option>
        if cmdline_args
            cmdline_args.each do |option, value|
                if value
                   if value.respond_to?(:to_ary)
                        value.each do |v|
                            cmdline.push "--#{option}=#{v}"
                        end
                   else
                       cmdline.push "--#{option}=#{value}"
                   end
                else
                    cmdline.push "--#{option}"
                end
            end
        end
		read.close
		write.fcntl(Fcntl::F_SETFD, 1)
		::Process.setpgrp
        begin
            if working_directory
                Dir.chdir(working_directory)
            end
            exec(*cmdline)
        rescue Exception
            write.write("FAILED")
        end
	    end
    Process.register(self)

	    write.close
	    if read.read == "FAILED"
		raise "cannot start #{name}"
	    end

    if gdb
        Orocos.warn "process #{name} has been started under gdbserver, port=#{gdb_port}. The components will not be functional until you attach a GDB to the started server"
    end

    if wait
        timeout = if wait.kind_of?(Numeric)
                      wait
                  elsif wait
                      Float::INFINITY
                  end
        wait_running(timeout, name_service)
    end
end

#wait_running(timeout = nil, name_service = Orocos::CORBA.name_service) ⇒ Object

Wait for the module to be started. If timeout is 0, the function returns immediately, with a false return value if the module is not started yet and a true return value if it is started.

Otherwise, it waits for the process to start for the specified amount of seconds. It will throw Orocos::NotFound if the process was not started within that time.

If timeout is nil, the method will wait indefinitely


1130
1131
1132
# File 'lib/orocos/process.rb', line 1130

def wait_running(timeout = nil, name_service = Orocos::CORBA.name_service)
           Process.wait_running(self, timeout, name_service)
end