Class: Orocos::Process
- Inherits:
-
ProcessBase
- Object
- ProcessBase
- Orocos::Process
- 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.
Defined Under Namespace
Classes: CommandLine, TaskNameRequired
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
-
.registered_processes ⇒ {Integer=>Process}
A map of existing running processes.
Instance Attribute Summary collapse
-
#binfile ⇒ Object
readonly
The path to the binary file.
-
#pid ⇒ Object
readonly
The component process ID.
Attributes inherited from ProcessBase
#default_logger, #logged_ports, #model, #name, #name_mappings, #tasks
Class Method Summary collapse
- .allocate_gdb_port ⇒ Object
-
.deregister(pid) ⇒ Object
Deregisters a process object that was registered with Process.register.
-
.each {|process| ... } ⇒ Object
Enumerates all registered processes.
-
.from_pid(pid) ⇒ nil, Process
Returns the process that has the given PID.
- .gdb_base_port=(port) ⇒ Object
-
.has_command?(cmd) ⇒ Boolean
private
Checks that the given command can be resolved.
-
.kill(processes, wait = true) ⇒ Object
Kills the given processes.
- .normalize_wait_option(wait, valgrind, gdb) ⇒ Object private
-
.parse_cmdline_wrapper_option(cmd, deployments, options, all_deployments) ⇒ Object
private
Normalizes the options for command line wrappers such as gdb and valgrind as passed to run.
-
.parse_log_level_option(options, all_deployments) ⇒ Hash<String,Symbol>
private
Normalizes the log_level option passed to run.
-
.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)
private
Separate the list of deployments from the spawn options in options passed to run.
-
.partition_run_options(*names, loader: Orocos.default_loader) ⇒ Object
Converts the options given to Orocos.run in a more normalized format.
-
.register(process) ⇒ void
Registers a PID-to-process mapping.
- .resolve_all_tasks(process, cache = Hash.new) ⇒ Object
-
.resolve_name_mappings(deployments, models) ⇒ Array<(String,Hash,String)>
private
Resolve the 'prefix' options given to run into an exhaustive task name mapping.
-
.run(*args, **options) ⇒ Object
deprecated
Deprecated.
use run directly instead
-
.try_task_cleanup(task) ⇒ Object
Tries to stop and cleanup the provided task.
-
.wait_running(process, timeout = nil, name_service = Orocos::CORBA.name_service, &block) ⇒ Object
Wait for a process to become reachable.
Instance Method Summary collapse
-
#alive? ⇒ Boolean
True if the process is running.
-
#command_line(working_directory: Orocos.default_working_directory, log_level: nil, cmdline_args: Hash.new, tracing: Orocos.tracing?, gdb: nil, valgrind: nil, name_service_ip: Orocos::CORBA.name_service_ip) ⇒ CommandLine
Massages various spawn parameters into the actual deployment command line.
-
#dead!(exit_status) ⇒ Object
Called externally to announce a component dead.
-
#host_id ⇒ Object
A string describing the host.
-
#initialize(name, model_name = name) ⇒ Process
constructor
Creates a new Process instance which will be able to start and supervise the execution of the given Orocos component.
-
#join ⇒ Object
Waits until the process dies.
-
#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.
-
#on_localhost? ⇒ Boolean
Returns true if the process is located on the same host than the Ruby interpreter.
- #resolve_all_tasks(cache = Hash.new, name_service: Orocos::CORBA.name_service) ⇒ Object
-
#running? ⇒ Boolean
True if the process is running.
-
#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.
-
#wait_running(timeout = nil, name_service = Orocos::CORBA.name_service) ⇒ Object
Wait for the module to be started.
Methods inherited from ProcessBase
#default_log_file_name, #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
423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 |
# File 'lib/orocos/process.rb', line 423 def initialize(name, model = name, loader: Orocos.default_pkgconfig_loader, name_mappings: Hash.new) model = if model.respond_to?(:to_str) loader.deployment_model_from_name(model) else model end @binfile = if loader.respond_to?(:find_deployment_binfile) loader.find_deployment_binfile(model.name) else loader.available_deployments[model.name].binfile end super(name, model, name_mappings: name_mappings) end |
Class Attribute Details
.registered_processes ⇒ {Integer=>Process}
A map of existing running processes
363 364 365 |
# File 'lib/orocos/process.rb', line 363 def registered_processes @registered_processes end |
Instance Attribute Details
#binfile ⇒ Object (readonly)
The path to the binary file
344 345 346 |
# File 'lib/orocos/process.rb', line 344 def binfile @binfile end |
#pid ⇒ Object (readonly)
The component process ID
346 347 348 |
# File 'lib/orocos/process.rb', line 346 def pid @pid end |
Class Method Details
.allocate_gdb_port ⇒ Object
872 873 874 |
# File 'lib/orocos/process.rb', line 872 def self.allocate_gdb_port @@gdb_port += 1 end |
.deregister(pid) ⇒ Object
Deregisters a process object that was registered with register
385 386 387 388 389 390 |
# File 'lib/orocos/process.rb', line 385 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
395 396 397 |
# File 'lib/orocos/process.rb', line 395 def self.each(&block) registered_processes.each_value(&block) end |
.from_pid(pid) ⇒ nil, Process
Returns the process that has the given PID
352 353 354 355 356 |
# File 'lib/orocos/process.rb', line 352 def self.from_pid(pid) if result = registered_processes[pid] return result end end |
.gdb_base_port=(port) ⇒ Object
867 868 869 |
# File 'lib/orocos/process.rb', line 867 def self.gdb_base_port=(port) @@gdb_port = port - 1 end |
.has_command?(cmd) ⇒ Boolean
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.
Checks that the given command can be resolved
697 698 699 700 701 702 703 |
# File 'lib/orocos/process.rb', line 697 def self.has_command?(cmd) if File.file?(cmd) && File.executable?(cmd) return else system("which #{cmd} > /dev/null 2>&1") end end |
.kill(processes, wait = true) ⇒ Object
Kills the given processes
860 861 862 863 864 865 |
# File 'lib/orocos/process.rb', line 860 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
571 572 573 574 575 576 577 578 579 580 581 582 |
# File 'lib/orocos/process.rb', line 571 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
732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 |
# File 'lib/orocos/process.rb', line 732 def self.parse_cmdline_wrapper_option(cmd, deployments, , all_deployments) if !deployments return Hash.new end if !has_command?(cmd) 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] = ; 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
686 687 688 689 690 691 692 |
# File 'lib/orocos/process.rb', line 686 def self.parse_log_level_option( , all_deployments ) if !.respond_to?(:to_hash) all_deployments.inject(Hash.new) { |h, name| h[name] = ; h } else 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:
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 670 671 672 673 |
# File 'lib/orocos/process.rb', line 638 def self.(*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 = (*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, , all_deployments) gdb = parse_cmdline_wrapper_option( 'gdbserver', gdb, , 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 = 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, ] end return processes, wait end |
.partition_run_options(*names, loader: Orocos.default_loader) ⇒ Object
Converts the options given to Orocos.run in a more normalized format
It returns a triple (deployments, models, options) where
-
c deployments is a map from a deployment name to a prefix that should be used to run this deployment. Prefixes are prepended to all task names in the deployment. It is set to nil if there are no prefix.
-
c models is a mapping from a oroGen model name to a name. It requests to start the default deployment for the model_name, using c name as the task name
-
options are options that should be passed to #spawn
For instance, in
Orocos.run 'xsens', 'xsens_imu::Task' => 'imu', :valgrind => true
One deployment called 'xsens' should be called with no prefix, the default deployment for xsens_imu::Task should be started and the corresponding task be renamed to 'imu' and all deployments should be started with the :valgrind => true option. Therefore, the parsed options would be
deployments = { 'xsens' => nil }
models = { 'xsens_imu::Task' => 'imu' }
= { valgrind => true }
In case multiple instances of a single model need to be started, the names can be given as an Array. E.g.
Orocos.run 'xsens_imu::Task' => ['imu1', 'imu2']
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 562 563 564 565 |
# File 'lib/orocos/process.rb', line 529 def self.(*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 OroGen::NotFound, "#{object} is neither a task model nor a deployment name" end end end case object when OroGen::Spec::TaskContext if !new_name raise TaskNameRequired, "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
374 375 376 377 378 379 380 |
# File 'lib/orocos/process.rb', line 374 def self.register(process) if !process.alive? raise ArgumentError, "cannot register a non-running process" end registered_processes[process.pid] = process nil end |
.resolve_all_tasks(process, cache = Hash.new) ⇒ Object
1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 |
# File 'lib/orocos/process.rb', line 1149 def self.resolve_all_tasks(process, cache = Hash.new) # 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| begin cache[task_name] ||= yield(task_name) rescue Orocos::NotFound end end if all_reachable cache end 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
771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 |
# File 'lib/orocos/process.rb', line 771 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
use Orocos.run directly instead
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 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 |
# File 'lib/orocos/process.rb', line 798 def self.run(*args, **) 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 = (*args, **) # Then spawn them, but without waiting for them processes = process_specs.map do |deployment_name, name_mappings, name, | p = Process.new(name, deployment_name) name_mappings.each do |old, new| p.map_name old, new end p.spawn() 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. 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
1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 |
# File 'lib/orocos/process.rb', line 1243 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.}" 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
1165 1166 1167 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 |
# File 'lib/orocos/process.rb', line 1165 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
455 |
# File 'lib/orocos/process.rb', line 455 def alive?; !!@pid end |
#command_line(working_directory: Orocos.default_working_directory, log_level: nil, cmdline_args: Hash.new, tracing: Orocos.tracing?, gdb: nil, valgrind: nil, name_service_ip: Orocos::CORBA.name_service_ip) ⇒ CommandLine
Massages various spawn parameters into the actual deployment command line
883 884 885 886 887 888 889 890 891 892 893 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 |
# File 'lib/orocos/process.rb', line 883 def command_line(working_directory: Orocos.default_working_directory, log_level: nil, cmdline_args: Hash.new, tracing: Orocos.tracing?, gdb: nil, valgrind: nil, name_service_ip: Orocos::CORBA.name_service_ip) result = CommandLine.new(Hash.new, nil, [], working_directory) result.command = binfile if tracing result.env['LD_PRELOAD'] = Orocos.tracing_library_path end if log_level valid_levels = [:debug, :info, :warn, :error, :fatal, :disable] if valid_levels.include?(log_level) result.env['BASE_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 if name_service_ip result.env['ORBInitRef'] = "NameService=corbaname::#{name_service_ip}" end cmdline_args = cmdline_args.dup cmdline_args[:rename] ||= [] name_mappings.each do |old, new| cmdline_args[:rename].push "#{old}:#{new}" end # Command line arguments have to be of type --<option>=<value> # or if <value> is nil a valueless option, i.e. --<option> cmdline_args.each do |option, value| if value if value.respond_to?(:to_ary) value.each do |v| result.args.push "--#{option}=#{v}" end else result.args.push "--#{option}=#{value}" end else result.args.push "--#{option}" end end if gdb result.args.unshift(result.command) if gdb == true gdb = Process.allocate_gdb_port end result.args.unshift("0.0.0.0:#{gdb}") result.command = 'gdbserver' elsif valgrind result.args.unshift(result.command) result.command = 'valgrind' end return result end |
#dead!(exit_status) ⇒ Object
Called externally to announce a component dead.
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 491 492 |
# File 'lib/orocos/process.rb', line 460 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_id ⇒ Object
A string describing the host. It can be used to check if two processes are running on the same host
401 402 403 |
# File 'lib/orocos/process.rb', line 401 def host_id 'localhost' end |
#join ⇒ Object
Waits until the process dies
This is valid only if the module has been started under Orocos supervision, using #spawn
443 444 445 446 447 448 449 450 451 452 |
# File 'lib/orocos/process.rb', line 443 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.
1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 |
# File 'lib/orocos/process.rb', line 1268 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
407 408 409 |
# File 'lib/orocos/process.rb', line 407 def on_localhost? host_id == 'localhost' end |
#resolve_all_tasks(cache = Hash.new, name_service: Orocos::CORBA.name_service) ⇒ Object
1215 1216 1217 1218 1219 |
# File 'lib/orocos/process.rb', line 1215 def resolve_all_tasks(cache = Hash.new, name_service: Orocos::CORBA.name_service) Process.resolve_all_tasks(self, cache) do |task_name| name_service.get(task_name) end end |
#running? ⇒ Boolean
True if the process is running
457 |
# File 'lib/orocos/process.rb', line 457 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
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 1068 1069 1070 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 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 |
# File 'lib/orocos/process.rb', line 977 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' = if valgrind.respond_to?(:to_ary) valgrind else [] end elsif gdb cmdline_wrapper = 'gdbserver' = if gdb.respond_to?(:to_ary) gdb else [] end gdb_port = Process.allocate_gdb_port << "localhost:#{gdb_port}" end if !name_service.ip.empty? ENV['ORBInitRef'] = "NameService=corbaname::#{name_service.ip}" end cmdline = [binfile] # 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.(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.(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 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
1230 1231 1232 |
# File 'lib/orocos/process.rb', line 1230 def wait_running(timeout = nil, name_service = Orocos::CORBA.name_service) Process.wait_running(self, timeout, name_service) end |