Class: ROS::Node

Inherits:
Object
  • Object
show all
Includes:
Name
Defined in:
lib/ros/node.rb

Overview

main interface of rosruby.

Examples:

Sample for Publisher

node = ROS::Node.new('/rosruby/sample_publisher')
publisher = node.advertise('/chatter', Std_msgs::String)
sleep(1)
msg = Std_msgs::String.new
i = 0
while node.ok?
  msg.data = "Hello, rosruby!: #{i}"
  publisher.publish(msg)

Sample for Subscriber

node = ROS::Node.new('/rosruby/sample_subscriber')
node.subscribe('/chatter', Std_msgs::String) do |msg|
  puts "message come! = \'#{msg.data}\'"
end

while node.ok?
  node.spin_once
  sleep(1)
end

Constant Summary

@@shutdown_hook =

for node shutdown hook

[]

Constants included from Name

ROS::Name::SEP

Instance Attribute Summary (collapse)

Instance Method Summary (collapse)

Methods included from Name

#anonymous_name, #canonicalize_name, #expand_local_name, #resolve_name_with_call_id

Constructor Details

- (Node) initialize(node_name, options = {})

initialization of ROS node get env, parse args, and start slave xmlrpc servers.

Parameters:

  • node_name (String)

    name of this node

  • options (Hash) (defaults to: {})

    options

Options Hash (options):

  • :anonymous (Boolean) — default: false

    use anonymous name if true. anonymous node generates a unique name

[View source]

64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
# File 'lib/ros/node.rb', line 64

def initialize(node_name, options={})
  @remappings = {}
  # @host is rewrited by ARGS[ROS_IP] or ARGS[ROS_HOSTNAME]
  @host = Socket.gethostname
  get_env
  if options[:anonymous]
    node_name = anonymous_name(node_name)
  end
  @node_name = resolve_name(node_name)
  @remappings = parse_args(ARGV)
  if not @master_uri
    raise 'ROS_MASTER_URI is nos set. please check environment variables'
  end

  @manager = GraphManager.new(@node_name, @master_uri, @host)
  @parameter = ParameterManager.new(@master_uri, @node_name, @remappings)

  if not @manager.check_master_connection
    puts "Unable to immediately register with master node [#{@master_uri}]: master may not be running yet. Will keep trying."
    while not @manager.check_master_connection
      sleep(1)
    end
  end

  if not options[:nologger]
    @logger = ::ROS::Log.new(self)
  end
  # use sim time
  ROS::Time.initialize_with_sim_or_wall(self)

  # because xmlrpc server use signal trap, after serve, it have to trap sig      trap_signals
  ObjectSpace.define_finalizer(self, proc {|id| self.shutdown})
end

Instance Attribute Details

- (String) host (readonly)

hostname of this node.

Returns:

  • (String)

    host name


119
120
121
# File 'lib/ros/node.rb', line 119

def host
  @host
end

- (String) master_uri (readonly)

URI of master

Returns:

  • (String)

    uri string of master


109
110
111
# File 'lib/ros/node.rb', line 109

def master_uri
  @master_uri
end

- (String) node_name (readonly)

name of this node (caller_id).

Returns:

  • (String)

    name of this node (=caller_id)


123
124
125
# File 'lib/ros/node.rb', line 123

def node_name
  @node_name
end

Instance Method Details

start publishing the topic.

Parameters:

  • topic_name (String)

    name of topic (string)

  • topic_type (Class)

    topic class

  • options (Hash) (defaults to: {})

    :latched, :resolve

Options Hash (options):

  • :latched (Boolean) — default: false

    latched topic

  • :resolve (Boolean) — default: true

    resolve topic_name or not. This is for publish /rosout with namespaced node.

Returns:

[View source]

195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
# File 'lib/ros/node.rb', line 195

def advertise(topic_name, topic_type, options={})
  if options[:no_resolve]
    name = topic_name
  else
    name = resolve_name(topic_name)
  end
  publisher = Publisher.new(@node_name,
                            name,
                            topic_type,
                            options[:latched],
                            @manager.host)
  @manager.add_publisher(publisher)
  trap_signals
  publisher
end

start service server.

Parameters:

  • service_name (String)

    name of this service (string)

  • service_type (Service)

    service class

  • callback (Proc)

    service definition

Returns:

[View source]

218
219
220
221
222
223
224
225
226
227
# File 'lib/ros/node.rb', line 218

def advertise_service(service_name, service_type, &callback)
  server = ::ROS::ServiceServer.new(@node_name,
                                    resolve_name(service_name),
                                    service_type,
                                    callback,
                                    @manager.host)
  @manager.add_service_server(server)
  trap_signals
  server
end

- (Boolean) delete_param(key)

delete the parameter for 'key'

Parameters:

  • key (String)

    key for delete

Returns:

  • (Boolean)

    true if success, false if it is not exist

[View source]

173
174
175
# File 'lib/ros/node.rb', line 173

def delete_param(key)
  @parameter.delete_param(expand_local_name(@node_name, key))
end

- (String, ...) get_param(key, default = nil)

get the param for key. You can set default value. That is uesed when the key is not set yet.

Parameters:

  • key (String)

    key for search the parameters

  • default (String, Integer, Float, Boolean) (defaults to: nil)

    default value

Returns:

  • (String, Integer, Float, Boolean)

    parameter value for key

[View source]

141
142
143
144
145
146
147
148
149
# File 'lib/ros/node.rb', line 141

def get_param(key, default=nil)
  key = expand_local_name(@node_name, key)
  param = @parameter.get_param(key)
  if param
    param
  else
    default
  end
end

- (Array) get_param_names

get all parameters.

Returns:

  • (Array)

    all parameter list

[View source]

156
157
158
# File 'lib/ros/node.rb', line 156

def get_param_names
  @parameter.get_param_names
end

- (Array) get_published_topics

get all topics by this node.

Returns:

  • (Array)

    topic names

[View source]

369
370
371
372
373
# File 'lib/ros/node.rb', line 369

def get_published_topics
  @manager.publishers.map do |pub|
    pub.topic_name
  end
end

- (Boolean) has_param(key)

check if the parameter server has the param for 'key'.

Parameters:

  • key (String)

    key for check

Returns:

  • (Boolean)

    true if exits

[View source]

164
165
166
# File 'lib/ros/node.rb', line 164

def has_param(key)
  @parameter.has_param(expand_local_name(@node_name, key))
end

- (Node) logdebug(message)

outputs log message for DEBUG

Parameters:

  • message (String)

    message for output

Returns:

[View source]

324
325
326
327
328
# File 'lib/ros/node.rb', line 324

def logdebug(message)
  file, line, function = caller[0].split(':')
  @logger.log('DEBUG', message, file, function, line.to_i)
  self
end

- (Node) logerror(message) Also known as: logerr

outputs log message for ERROR.

Parameters:

  • message (String)

    message for output

Returns:

[View source]

346
347
348
349
350
# File 'lib/ros/node.rb', line 346

def logerror(message)
  file, line, function = caller[0].split(':')
  @logger.log('ERROR', message, file, function, line.to_i)
  self
end

- (Node) logfatal(message)

outputs log message for FATAL.

Parameters:

  • message (String)

    message for output

Returns:

[View source]

359
360
361
362
363
# File 'lib/ros/node.rb', line 359

def logfatal(message)
  file, line, function = caller[0].split(':')
  @logger.log('FATAL', message, file, function, line.to_i)
  self
end

- (Node) loginfo(message)

outputs log message for INFO (INFORMATION).

Parameters:

  • message (String)

    message for output

Returns:

[View source]

314
315
316
317
318
# File 'lib/ros/node.rb', line 314

def loginfo(message)
  file, line, function = caller[0].split(':')
  @logger.log('INFO', message, file, function, line.to_i)
  self
end

- (Node) logwarn(message)

outputs log message for WARN (WARING).

Parameters:

  • message (String)

    message for output

Returns:

[View source]

335
336
337
338
339
# File 'lib/ros/node.rb', line 335

def logwarn(message)
  file, line, function = caller[0].split(':')
  @logger.log('WARN', message, file, function, line.to_i)
  self
end

- (Boolean) ok?

Is this node running? Please use for 'while loop' and so on..

Returns:

  • (Boolean)

    true if node is running.

[View source]

103
104
105
# File 'lib/ros/node.rb', line 103

def ok?
  @manager.is_ok?
end

- (String) resolve_name(name)

resolve the name by this node's remapping rule.

Parameters:

  • name (String)

    name for resolved

Returns:

  • (String)

    resolved name

[View source]

130
131
132
# File 'lib/ros/node.rb', line 130

def resolve_name(name)
  resolve_name_with_call_id(@node_name, @ns, name, @remappings)
end

- (ServiceClient) service(service_name, service_type)

create service client.

Parameters:

  • service_name (String)

    name of this service (string)

  • service_type (Class)

    service class

Returns:

[View source]

243
244
245
246
247
248
# File 'lib/ros/node.rb', line 243

def service(service_name, service_type)
  ROS::ServiceClient.new(@master_uri,
                         @node_name,
                         resolve_name(service_name),
                         service_type)
end

- (Boolean) set_param(key, value)

set parameter for 'key'.

Parameters:

  • key (String)

    key of parameter

  • value (String, Integer, Float, Boolean)

    value of parameter

Returns:

  • (Boolean)

    return true if succeed

[View source]

182
183
184
# File 'lib/ros/node.rb', line 182

def set_param(key, value)
  @parameter.set_param(expand_local_name(@node_name, key), value)
end

- (Node) shutdown

unregister to master and shutdown all connections.

Returns:

[View source]

298
299
300
301
302
303
304
305
306
307
308
# File 'lib/ros/node.rb', line 298

def shutdown
  if ok?
    begin
      @manager.shutdown
    rescue => message
      p message
      puts 'ignoring errors while shutdown'
    end
  end
  self
end

- (String) slave_uri

get node URI

Returns:

  • (String)

    uri of this node’s api

[View source]

113
114
115
# File 'lib/ros/node.rb', line 113

def slave_uri
  @manager.get_uri
end

- (Object) spin

spin forever.

[View source]

288
289
290
291
292
293
# File 'lib/ros/node.rb', line 288

def spin
  while ok?
    spin_once
    sleep(0.01)
  end
end

- (Object) spin_once

spin once. This invoke subscription/service_server callbacks

[View source]

281
282
283
# File 'lib/ros/node.rb', line 281

def spin_once
  @manager.spin_once
end

- (Subscriber) subscribe(topic_name, topic_type, &callback)

start to subscribe a topic.

Parameters:

  • topic_name (String)

    name of topic (string)

  • topic_type (Class)

    Topic instance

Returns:

[View source]

256
257
258
259
260
261
262
263
264
# File 'lib/ros/node.rb', line 256

def subscribe(topic_name, topic_type, &callback)
  sub = Subscriber.new(@node_name,
                       resolve_name(topic_name),
                       topic_type,
                       callback)
  @manager.add_subscriber(sub)
  trap_signals
  sub
end

- (ParameterSubscriber) subscribe_parameter(param, &callback)

subscribe to the parameter.

Parameters:

  • param (String)

    name of parameter to subscribe

  • callback (Proc)

    callback when parameter updated

Returns:

[View source]

272
273
274
275
276
# File 'lib/ros/node.rb', line 272

def subscribe_parameter(param, &callback)
  sub = ParameterSubscriber.new(param, callback)
  @manager.add_parameter_subscriber(sub)
  sub
end

- (Boolean) wait_for_service(service_name, timeout_sec = nil)

wait until start the service.

Parameters:

  • service_name (String)

    name of service for waiting

  • timeout_sec (Float) (defaults to: nil)

    time out seconds. default infinity.

Returns:

  • (Boolean)

    true if success, false if timeout

[View source]

234
235
236
# File 'lib/ros/node.rb', line 234

def wait_for_service(service_name, timeout_sec=nil)
  @manager.wait_for_service(service_name, timeout_sec)
end