Class: Orocos::ROS::Node
- Inherits:
-
TaskContextBase
- Object
- TaskContextBase
- Orocos::ROS::Node
- Defined in:
- lib/orocos/ros/node.rb
Overview
A TaskContext-compatible interface of a ROS node
The following caveats apply:
-
ROS nodes do not have an internal lifecycle state machine. In practice, it means that #configure has no effect, #start will start the node's process and #stop will kill it (if we have access to it). If the ROS process is not managed by orocos.rb, they will throw
-
ROS nodes do not allow modifying subscriptions at runtime, so the port connection / disconnection methods can only be used while the node is not running
Constant Summary
Constants inherited from TaskContextBase
TaskContextBase::RUNNING_STATES
Constants included from Namespace
Instance Attribute Summary collapse
-
#doc ⇒ Object
readonly
Returns the value of attribute doc.
-
#exit_status ⇒ Integer
readonly
If started by this Ruby process, and then stopped, the exit status object that represents how the node finished.
-
#name_mappings ⇒ NameMappings
readonly
The name mappings that are applied from the node implementation to this running node.
-
#name_service ⇒ Object
readonly
- NameService
-
access to the state of the ROS graph.
-
#pid ⇒ Integer
readonly
If started by this Ruby process, the PID of the ROS node process.
-
#server ⇒ Object
readonly
- ROSSlave
-
access to the node XMLRPC API.
-
#topics ⇒ Object
readonly
- Hash<String,Topic>
-
a cache of the topics that are known to be associated with this node.
Attributes inherited from TaskContextBase
#attributes, #configuration_log, #current_state, #ior, #process, #properties, #state_symbols
Instance Method Summary collapse
- #==(other) ⇒ Object
-
#apply_name_mappings(name) ⇒ Object
Applies the name mappings configured on this node on the given name.
- #attribute_names ⇒ Object
- #cleanup(wait_for_completion = true) ⇒ Object
- #configure(wait_for_completion = true) ⇒ Object
- #dead!(exit_status) ⇒ Object
- #doc? ⇒ Boolean
-
#each_input_port(verify = true) ⇒ Object
Enumerates each “input topics” of this node.
-
#each_output_port(verify = true) ⇒ Object
Enumerates each “output topics” of this node.
- #each_port(verify = true) ⇒ Object
- #each_property ⇒ Object
-
#find_input_port(name, verify = true, wait_if_unavailable = true) ⇒ ROS::Topic?
Finds the name of a topic this node is subscribed to.
-
#find_output_port(name, verify = true, wait_if_unavailable = true) ⇒ ROS::Topic?
Finds the name of a topic this node is publishing.
- #has_port?(name) ⇒ Boolean
-
#implements?(class_name) ⇒ Boolean
True if this task's model is a subclass of the provided class name.
-
#initialize(name_service, server, name = nil, options = Hash.new) ⇒ Node
constructor
A new instance of Node.
- #input_port(name, verify = true) ⇒ Object
- #join ⇒ Object
- #kill ⇒ Object
- #log_all_configuration(logfile) ⇒ Object
- #operation_names ⇒ Object
- #output_port(name, verify = true) ⇒ Object
-
#ping ⇒ Object
Tests if this node is still available.
- #port(name, verify = true) ⇒ Object
- #port_names ⇒ Object
- #pretty_print(pp) ⇒ Object
- #property_names ⇒ Object
-
#reachable? ⇒ Boolean
Tests if this node is still available on the ROS system.
- #reset_exception(wait_for_completion = true) ⇒ Object
-
#resolve_input_topic_name(topic_name) ⇒ (String,OroGen::ROS::Spec::InputTopic), (String,nil)
Resolves the given topic name into a port name and a port model.
-
#resolve_output_topic_name(topic_name) ⇒ (String,OroGen::ROS::Spec::OutputTopic), (String,nil)
Resolves the given topic name into a port name and a port model.
- #ros_name ⇒ Object
- #rtt_state ⇒ Object
-
#running? ⇒ Boolean
True if this Node is already running (somewhere) and false otherwise.
- #shutdown(wait_for_completion = true) ⇒ Object
-
#spawn ⇒ Object
Starts this node.
- #start(wait_for_completion = true) ⇒ Object
- #stop(wait_for_completion = true) ⇒ Object
-
#to_async(options = Hash.new) ⇒ Orocos::Async::ROS::Node
An object that gives asynchronous access to this particular ROS node.
- #to_proxy(options = Hash.new) ⇒ Object
-
#wait_running(timeout = nil) ⇒ Object
Waits for this node to be available.
Methods inherited from TaskContextBase
#add_default_states, #available_states, #basename, connect_to, #connect_to, #each_attribute, #each_operation, #error?, #error_state?, #exception?, #exception_state?, #fatal_error?, #fatal_error_state?, find_one_running, get, get_provides, #has_attribute?, #has_operation?, #has_property?, #info, #input_port_model, #inspect, #method_missing, #model, #model=, #name, #on_localhost?, #output_port_model, #peek_current_state, #peek_state, #ports, #pre_operational?, reachable?, #ready?, #runtime_error?, #runtime_state?, #state, #state_changed?, #states, #to_h, #to_s, #toplevel_state
Methods included from Namespace
#basename, #map_to_namespace, #namespace, #namespace=, #same_namespace?, #split_name, split_name, validate_namespace_name, #verify_same_namespace
Methods included from PortsSearchable
#find_all_input_ports, #find_all_output_ports, #find_all_ports, #find_port
Methods included from TaskContextBaseAbstract
#attribute, #operation, #property
Constructor Details
#initialize(name_service, server, name = nil, options = Hash.new) ⇒ Node
Returns a new instance of Node
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 |
# File 'lib/orocos/ros/node.rb', line 35 def initialize(name_service, server, name = nil, = Hash.new) @name_service = name_service @server = server @input_topics = Hash.new @output_topics = Hash.new @name_mappings = NameMappings.new if name.kind_of?(Hash) name, = nil, name end with_defaults, = Kernel. , :model => OroGen::ROS::Spec::Node.new(nil,name), :namespace => name_service.namespace = .merge(with_defaults) # We allow models to be specified by name if [:model].respond_to?(:to_str) [:model] = Orocos.default_loader.task_model_from_name([:model]) end # Initialize the name from the model if it has one, and no name # was given if !name if [:model] name = [:model].name.gsub(/.*::/, '') else raise ArgumentError, "no name and no model given. At least one of the two must be provided." end end super(name, ) if running? @state_queue << :RUNNING else @state_queue << :PRE_OPERATIONAL end end |
Dynamic Method Handling
This class handles dynamic methods through the method_missing method in the class Orocos::TaskContextBase
Instance Attribute Details
#doc ⇒ Object (readonly)
Returns the value of attribute doc
244 245 246 |
# File 'lib/orocos/ros/node.rb', line 244 def doc @doc end |
#exit_status ⇒ Integer (readonly)
Returns if started by this Ruby process, and then stopped, the exit status object that represents how the node finished
33 34 35 |
# File 'lib/orocos/ros/node.rb', line 33 def exit_status @exit_status end |
#name_mappings ⇒ NameMappings (readonly)
Returns the name mappings that are applied from the node implementation to this running node. This is useful only when using a model
27 28 29 |
# File 'lib/orocos/ros/node.rb', line 27 def name_mappings @name_mappings end |
#name_service ⇒ Object (readonly)
- NameService
-
access to the state of the ROS graph
17 18 19 |
# File 'lib/orocos/ros/node.rb', line 17 def name_service @name_service end |
#pid ⇒ Integer (readonly)
Returns if started by this Ruby process, the PID of the ROS node process
30 31 32 |
# File 'lib/orocos/ros/node.rb', line 30 def pid @pid end |
#server ⇒ Object (readonly)
- ROSSlave
-
access to the node XMLRPC API
19 20 21 |
# File 'lib/orocos/ros/node.rb', line 19 def server @server end |
#topics ⇒ Object (readonly)
- Hash<String,Topic>
-
a cache of the topics that are known to be
associated with this node. It should never be used directly, as it may contain stale entries. The key is the port name of the topic
23 24 25 |
# File 'lib/orocos/ros/node.rb', line 23 def topics @topics end |
Instance Method Details
#==(other) ⇒ Object
78 79 80 81 82 |
# File 'lib/orocos/ros/node.rb', line 78 def ==(other) other.class == self.class && other.name_service == self.name_service && other.name == self.name end |
#apply_name_mappings(name) ⇒ Object
Applies the name mappings configured on this node on the given name.
In effect, given a name from TaskContextBase#model, it gives the name of the corresponding object in the context of the running node
215 216 217 |
# File 'lib/orocos/ros/node.rb', line 215 def apply_name_mappings(name) name_mappings.apply(name) end |
#attribute_names ⇒ Object
253 |
# File 'lib/orocos/ros/node.rb', line 253 def attribute_names; [] end |
#cleanup(wait_for_completion = true) ⇒ Object
175 176 177 |
# File 'lib/orocos/ros/node.rb', line 175 def cleanup(wait_for_completion = true) # This is no-op for ROS nodes end |
#configure(wait_for_completion = true) ⇒ Object
119 120 121 122 123 124 125 126 127 |
# File 'lib/orocos/ros/node.rb', line 119 def configure(wait_for_completion = true) # This is a no-op for ROS nodes if state == :PRE_OPERATIONAL @state_queue << :STOPPED else ROS.warn "setting state of Orocos::ROS::Node '#{ros_name}' to #{state}, though true configuration of #{self} is not supported." raise StateTransitionFailed, "#{self} cannot be configured in state #{state}" end end |
#dead!(exit_status) ⇒ Object
90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 |
# File 'lib/orocos/ros/node.rb', line 90 def dead!(exit_status) exit_status = (@exit_status ||= exit_status) if !exit_status ROS.info "deployment #{name} exited, exit status unknown" elsif exit_status.success? ROS.info "deployment #{name} exited normally" elsif exit_status.signaled? if @expected_exit == exit_status.termsig ROS.info "ROS node #{name} terminated with signal #{exit_status.termsig}" elsif @expected_exit ROS.info "ROS node #{name} terminated with signal #{exit_status.termsig} but #{@expected_exit} was expected" else ROS.warn "ROS node #{name} unexpectedly terminated with signal #{exit_status.termsig}" @state_queue << :EXCEPTION end else ROS.warn "ROS node #{name} terminated with code #{exit_status.to_i}" @state_queue << :EXCEPTION end if @state_queue.last != :EXCEPTION @state_queue << :STOPPED end @pid = nil @server = nil end |
#doc? ⇒ Boolean
243 |
# File 'lib/orocos/ros/node.rb', line 243 def doc?; false end |
#each_input_port(verify = true) ⇒ Object
Enumerates each “input topics” of this node
371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 |
# File 'lib/orocos/ros/node.rb', line 371 def each_input_port(verify = true) return enum_for(:each_input_port, verify) if !block_given? if !verify return @input_topics.values.each(&proc) end if !running? model.each_input_port do |m| yield(@input_topics[m.name] ||= InputTopic.new(self, m.topic_name, m.topic_type, m.name)) end else name_service.input_topics_for(ros_name).each do |topic_name| topic_type = name_service.(topic_name) if ROS.(topic_type) name, model = resolve_input_topic_name(topic_name) topic = (@input_topics[name] ||= InputTopic.new(self, topic_name, topic_type, model, name)) yield(topic) end end end end |
#each_output_port(verify = true) ⇒ Object
Enumerates each “output topics” of this node
347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 |
# File 'lib/orocos/ros/node.rb', line 347 def each_output_port(verify = true) return enum_for(:each_output_port, verify) if !block_given? if !verify return @output_topics.values.each(&proc) end if !running? model.each_output_port do |m| yield(@output_topics[m.name] ||= OutputTopic.new(self, m.topic_name, m.topic_type, m.name)) end else name_service.output_topics_for(ros_name).each do |topic_name, topic_type| topic_type = name_service.(topic_name) if ROS.(topic_type) name, model = resolve_output_topic_name(topic_name) topic = (@output_topics[name] ||= OutputTopic.new(self, topic_name, topic_type, model, name)) yield(topic) end end end end |
#each_port(verify = true) ⇒ Object
318 319 320 321 322 |
# File 'lib/orocos/ros/node.rb', line 318 def each_port(verify = true) return enum_for(:each_port, verify) if !block_given? each_output_port(verify) { |p| yield(p) } each_input_port(verify) { |p| yield(p) } end |
#each_property ⇒ Object
246 |
# File 'lib/orocos/ros/node.rb', line 246 def each_property; end |
#find_input_port(name, verify = true, wait_if_unavailable = true) ⇒ ROS::Topic?
Finds the name of a topic this node is subscribed to
306 307 308 309 310 311 312 313 314 315 316 |
# File 'lib/orocos/ros/node.rb', line 306 def find_input_port(name, verify = true, wait_if_unavailable = true) each_input_port(verify) do |p| if p.name == name || p.topic_name == OroGen::ROS.normalize_topic_name(name) return p end end if verify && wait_if_unavailable name_service.wait_for_update find_input_port(name, true, false) end end |
#find_output_port(name, verify = true, wait_if_unavailable = true) ⇒ ROS::Topic?
Finds the name of a topic this node is publishing
291 292 293 294 295 296 297 298 299 300 301 |
# File 'lib/orocos/ros/node.rb', line 291 def find_output_port(name, verify = true, wait_if_unavailable = true) each_output_port(verify) do |p| if p.name == name || p.topic_name == OroGen::ROS.normalize_topic_name(name) return p end end if verify && wait_if_unavailable name_service.wait_for_update find_output_port(name, true, false) end end |
#has_port?(name) ⇒ Boolean
256 257 258 259 260 261 262 |
# File 'lib/orocos/ros/node.rb', line 256 def has_port?(name) verify = true if model.spec_available? verify = false end !!(find_output_port(name, verify) || find_input_port(name, verify)) end |
#implements?(class_name) ⇒ Boolean
True if this task's model is a subclass of the provided class name
This is available only if the deployment in which this task context runs has been generated by orogen.
223 224 225 |
# File 'lib/orocos/ros/node.rb', line 223 def implements?(class_name) model.implements?(class_name) end |
#input_port(name, verify = true) ⇒ Object
272 273 274 275 276 277 278 |
# File 'lib/orocos/ros/node.rb', line 272 def input_port(name, verify = true) p = find_input_port(name, verify) if !p raise Orocos::NotFound, "cannot find topic #{name} as a subscription of node #{self.name}" end p end |
#join ⇒ Object
164 165 166 167 168 169 170 171 172 173 |
# File 'lib/orocos/ros/node.rb', line 164 def join return if !running? begin ::Process.waitpid(pid) exit_status = $? dead!(exit_status) rescue Errno::ECHILD end end |
#kill ⇒ Object
160 161 162 |
# File 'lib/orocos/ros/node.rb', line 160 def kill ::Process.kill('INT', @pid) end |
#log_all_configuration(logfile) ⇒ Object
440 441 442 |
# File 'lib/orocos/ros/node.rb', line 440 def log_all_configuration(logfile) # n/a for ROS node end |
#operation_names ⇒ Object
254 |
# File 'lib/orocos/ros/node.rb', line 254 def operation_names; [] end |
#output_port(name, verify = true) ⇒ Object
280 281 282 283 284 285 286 |
# File 'lib/orocos/ros/node.rb', line 280 def output_port(name, verify = true) p = find_output_port(name, verify) if !p raise Orocos::NotFound, "cannot find topic #{name} as a publication of node #{self.name}" end p end |
#ping ⇒ Object
Tests if this node is still available
434 435 436 437 438 |
# File 'lib/orocos/ros/node.rb', line 434 def ping if !name_service.has_node?(name) raise Orocos::ComError, "ROS node #{name} is not available on the ROS graph anymore" end end |
#port(name, verify = true) ⇒ Object
264 265 266 267 268 269 270 |
# File 'lib/orocos/ros/node.rb', line 264 def port(name, verify = true) p = (find_output_port(name, verify) || find_input_port(name, verify)) if !p raise Orocos::NotFound, "cannot find topic #{name} attached to node #{self.name}" end p end |
#port_names ⇒ Object
248 249 250 |
# File 'lib/orocos/ros/node.rb', line 248 def port_names each_port.map(&:name) end |
#pretty_print(pp) ⇒ Object
394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 |
# File 'lib/orocos/ros/node.rb', line 394 def pretty_print(pp) pp.text "ROS Node #{name}" pp.breakable inputs = each_input_port.to_a outputs = each_output_port.to_a ports = enum_for(:each_port).to_a if ports.empty? pp.text "No ports" pp.breakable else pp.text "Ports:" pp.breakable pp.nest(2) do pp.text " " each_port do |port| port.pretty_print(pp) pp.breakable end end pp.breakable end end |
#property_names ⇒ Object
252 |
# File 'lib/orocos/ros/node.rb', line 252 def property_names; [] end |
#reachable? ⇒ Boolean
Tests if this node is still available on the ROS system
A node is reachable if it is still available on the ROS graph
236 237 238 239 240 241 |
# File 'lib/orocos/ros/node.rb', line 236 def reachable? name_service.has_node?(name) true rescue ComError false end |
#reset_exception(wait_for_completion = true) ⇒ Object
179 180 181 182 |
# File 'lib/orocos/ros/node.rb', line 179 def reset_exception(wait_for_completion = true) @state_queue << :STOPPED @exit_status = nil end |
#resolve_input_topic_name(topic_name) ⇒ (String,OroGen::ROS::Spec::InputTopic), (String,nil)
Resolves the given topic name into a port name and a port model.
337 338 339 340 341 342 343 344 |
# File 'lib/orocos/ros/node.rb', line 337 def resolve_input_topic_name(topic_name) model.each_input_port do |m| if apply_name_mappings(m.topic_name) == OroGen::ROS.normalize_topic_name(topic_name) return m.name, m end end return Topic.default_port_name(topic_name), nil end |
#resolve_output_topic_name(topic_name) ⇒ (String,OroGen::ROS::Spec::OutputTopic), (String,nil)
Resolves the given topic name into a port name and a port model.
326 327 328 329 330 331 332 333 |
# File 'lib/orocos/ros/node.rb', line 326 def resolve_output_topic_name(topic_name) model.each_output_port do |m| if apply_name_mappings(m.topic_name) == OroGen::ROS.normalize_topic_name(topic_name) return m.name, m end end return Topic.default_port_name(topic_name), nil end |
#ros_name ⇒ Object
73 74 75 76 |
# File 'lib/orocos/ros/node.rb', line 73 def ros_name _, basename = split_name(name) OroGen::ROS.rosnode_normalize_name(basename) end |
#rtt_state ⇒ Object
227 228 229 |
# File 'lib/orocos/ros/node.rb', line 227 def rtt_state @state_queue.last || @current_state end |
#running? ⇒ Boolean
Returns true if this Node is already running (somewhere) and false otherwise
86 87 88 |
# File 'lib/orocos/ros/node.rb', line 86 def running? !!server end |
#shutdown(wait_for_completion = true) ⇒ Object
150 151 152 153 154 155 156 157 158 |
# File 'lib/orocos/ros/node.rb', line 150 def shutdown(wait_for_completion = true) if !running? raise StateTransitionFailed, "#{self} is not running" end kill if wait_for_completion join end end |
#spawn ⇒ Object
Starts this node
185 186 187 188 189 190 |
# File 'lib/orocos/ros/node.rb', line 185 def spawn args = name_mappings.to_command_line package_name, bin_name = *model.name.split("::") binary = OroGen::ROS.rosnode_find(package_name.gsub(/^ros_/, ''), bin_name) @pid = Utilrb.spawn binary, "__name:=#{name}", *args end |
#start(wait_for_completion = true) ⇒ Object
129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 |
# File 'lib/orocos/ros/node.rb', line 129 def start(wait_for_completion = true) if running? if state == :RUNNING raise StateTransitionFailed, "#{self} is already running" else @state_queue << :RUNNING ROS.warn "setting state of Orocos::ROS::Node '#{ros_name}' to #{state}, though true start of #{self} is not performed, since the node was already started." end end spawn if wait_for_completion wait_running end end |
#stop(wait_for_completion = true) ⇒ Object
145 146 147 148 |
# File 'lib/orocos/ros/node.rb', line 145 def stop(wait_for_completion = true) @state_queue << :STOPPED ROS.warn "setting state of Orocos::ROS::Node '#{ros_name}' to #{state}, though true stopping of Orocos::ROS::Node is not performed. Use #shutdown for halting" end |
#to_async(options = Hash.new) ⇒ Orocos::Async::ROS::Node
Returns an object that gives asynchronous access to this particular ROS node
420 421 422 |
# File 'lib/orocos/ros/node.rb', line 420 def to_async( = Hash.new) Async::ROS::Node.new(name_service, server, name, ) end |
#to_proxy(options = Hash.new) ⇒ Object
424 425 426 427 428 429 |
# File 'lib/orocos/ros/node.rb', line 424 def to_proxy( = Hash.new) [:use] ||= to_async # use name service to check if there is already # a proxy for the task Orocos::Async.proxy(name,.merge(:name_service => name_service)) end |
#wait_running(timeout = nil) ⇒ Object
Waits for this node to be available
193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 |
# File 'lib/orocos/ros/node.rb', line 193 def wait_running(timeout = nil) return if @server now = Time.now while true begin node = name_service.get name @server = node.server break rescue Orocos::NotFound end if timeout && (Time.now - now) > timeout raise Orocos::NotFound, "#{self} is still not reachable after #{timeout} seconds" end end end |