rosruby 0.0.1
Sign up to get free protection for your applications and to get access to all the features.
- data/bin/rubyroscore +5 -0
- data/lib/ros.rb +25 -0
- data/lib/ros/duration.rb +63 -0
- data/lib/ros/graph_manager.rb +408 -0
- data/lib/ros/log.rb +72 -0
- data/lib/ros/master.rb +408 -0
- data/lib/ros/master_proxy.rb +256 -0
- data/lib/ros/message.rb +65 -0
- data/lib/ros/name.rb +88 -0
- data/lib/ros/node.rb +442 -0
- data/lib/ros/package.rb +144 -0
- data/lib/ros/parameter_manager.rb +127 -0
- data/lib/ros/parameter_subscriber.rb +47 -0
- data/lib/ros/publisher.rb +96 -0
- data/lib/ros/rate.rb +41 -0
- data/lib/ros/ros.rb +10 -0
- data/lib/ros/roscore.rb +29 -0
- data/lib/ros/service.rb +37 -0
- data/lib/ros/service_client.rb +83 -0
- data/lib/ros/service_server.rb +92 -0
- data/lib/ros/slave_proxy.rb +153 -0
- data/lib/ros/subscriber.rb +119 -0
- data/lib/ros/tcpros/client.rb +108 -0
- data/lib/ros/tcpros/header.rb +89 -0
- data/lib/ros/tcpros/message.rb +74 -0
- data/lib/ros/tcpros/server.rb +137 -0
- data/lib/ros/tcpros/service_client.rb +104 -0
- data/lib/ros/tcpros/service_server.rb +132 -0
- data/lib/ros/time.rb +109 -0
- data/lib/ros/topic.rb +47 -0
- data/lib/ros/xmlrpcserver.rb +40 -0
- data/samples/add_two_ints_client.rb +25 -0
- data/samples/add_two_ints_server.rb +20 -0
- data/samples/gui.rb +126 -0
- data/samples/sample_log.rb +16 -0
- data/samples/sample_param.rb +20 -0
- data/samples/sample_publisher.rb +20 -0
- data/samples/sample_subscriber.rb +19 -0
- data/scripts/genmsg_ruby.py +1135 -0
- data/scripts/genmsg_ruby.pyc +0 -0
- data/scripts/gensrv_ruby.py +105 -0
- data/scripts/gensrv_ruby.pyc +0 -0
- data/scripts/rosruby_genmsg.py +67 -0
- data/scripts/run-test.rb +21 -0
- data/test/test_header.rb +36 -0
- data/test/test_log.rb +45 -0
- data/test/test_master_proxy.rb +73 -0
- data/test/test_message.rb +13 -0
- data/test/test_node.rb +166 -0
- data/test/test_package.rb +10 -0
- data/test/test_param.rb +27 -0
- data/test/test_pubsub.rb +154 -0
- data/test/test_rate.rb +16 -0
- data/test/test_service.rb +34 -0
- data/test/test_slave_proxy.rb +49 -0
- data/test/test_time.rb +39 -0
- metadata +170 -0
data/lib/ros/ros.rb
ADDED
data/lib/ros/roscore.rb
ADDED
@@ -0,0 +1,29 @@
|
|
1
|
+
#!/usr/bin/env ruby
|
2
|
+
|
3
|
+
require 'ros/master'
|
4
|
+
require 'ros'
|
5
|
+
|
6
|
+
module ROS
|
7
|
+
|
8
|
+
def self.start_roscore
|
9
|
+
# master
|
10
|
+
thread = Thread.new do
|
11
|
+
ROS::Master.new.start
|
12
|
+
end
|
13
|
+
|
14
|
+
sleep 1
|
15
|
+
|
16
|
+
# rosout
|
17
|
+
rosout_node = ROS::Node.new('/rosout', :nologger=>true)
|
18
|
+
rosout_agg_publisher = rosout_node.advertise('/rosout_agg', Rosgraph_msgs::Log)
|
19
|
+
rosout_node.subscribe('/rosout', Rosgraph_msgs::Log) do |msg|
|
20
|
+
rosout_agg_publisher.publish(msg)
|
21
|
+
end
|
22
|
+
rosout_node.spin
|
23
|
+
end
|
24
|
+
end
|
25
|
+
|
26
|
+
if $0 == __FILE__
|
27
|
+
ROS::start_roscore
|
28
|
+
end
|
29
|
+
|
data/lib/ros/service.rb
ADDED
@@ -0,0 +1,37 @@
|
|
1
|
+
# ros/service.rb
|
2
|
+
#
|
3
|
+
# License: BSD
|
4
|
+
#
|
5
|
+
# Copyright (C) 2012 Takashi Ogura <t.ogura@gmail.com>
|
6
|
+
#
|
7
|
+
# Super Class of ServiceServer and ServiceClient
|
8
|
+
#
|
9
|
+
|
10
|
+
module ROS
|
11
|
+
|
12
|
+
##
|
13
|
+
# Super Class of ServiceServer and ServiceClient
|
14
|
+
#
|
15
|
+
class Service
|
16
|
+
|
17
|
+
#
|
18
|
+
# @param [String] caller_id caller_id of this node
|
19
|
+
# @param [String] service_name name of service (String)
|
20
|
+
# @param [class] service_type class of Service
|
21
|
+
def initialize(caller_id, service_name, service_type)
|
22
|
+
@caller_id = caller_id
|
23
|
+
@service_name = service_name
|
24
|
+
@service_type = service_type
|
25
|
+
end
|
26
|
+
|
27
|
+
# @return [String] caller id of this node
|
28
|
+
attr_reader :caller_id
|
29
|
+
|
30
|
+
# @return [String] service name (like '/add_two_ints')
|
31
|
+
attr_reader :service_name
|
32
|
+
|
33
|
+
# @return [Class] class instance of srv converted class (like Std_msgs/String)
|
34
|
+
attr_reader :service_type
|
35
|
+
|
36
|
+
end
|
37
|
+
end
|
@@ -0,0 +1,83 @@
|
|
1
|
+
# ros/service_client.rb
|
2
|
+
#
|
3
|
+
# License: BSD
|
4
|
+
#
|
5
|
+
# Copyright (C) 2012 Takashi Ogura <t.ogura@gmail.com>
|
6
|
+
#
|
7
|
+
|
8
|
+
require 'ros/service'
|
9
|
+
require 'ros/tcpros/service_client'
|
10
|
+
require 'uri'
|
11
|
+
|
12
|
+
module ROS
|
13
|
+
|
14
|
+
|
15
|
+
# This is an interface of ROS Service.
|
16
|
+
# {Node#service} returns {ServiceClient} instance.
|
17
|
+
# @example
|
18
|
+
# node = ROS::Node.new('/rosruby/sample_service_client')
|
19
|
+
# if node.wait_for_service('/add_two_ints', 1)
|
20
|
+
# service = node.service('/add_two_ints', Roscpp_tutorials::TwoInts)
|
21
|
+
# req = Roscpp_tutorials::TwoInts.request_class.new
|
22
|
+
# res = Roscpp_tutorials::TwoInts.response_class.new
|
23
|
+
# req.a = 1
|
24
|
+
# req.b = 2
|
25
|
+
# if service.call(req, res)
|
26
|
+
# p res.sum
|
27
|
+
# end
|
28
|
+
# end
|
29
|
+
class ServiceClient < Service
|
30
|
+
|
31
|
+
# @param [String] master_uri URI of ROS Master
|
32
|
+
# @param [String] caller_id caller id of this node
|
33
|
+
# @param [String] service_name name of service
|
34
|
+
# @param [Class] service_type class of srv
|
35
|
+
# @param [Boolean] persistent use persistent connection with server or not.
|
36
|
+
def initialize(master_uri, caller_id, service_name, service_type, persistent=false)
|
37
|
+
super(caller_id, service_name, service_type)
|
38
|
+
@master_uri = master_uri
|
39
|
+
@persistent = persistent
|
40
|
+
end
|
41
|
+
|
42
|
+
##
|
43
|
+
# get hostname and port from uri
|
44
|
+
# @param [String] uri decompose uri string to host and port
|
45
|
+
# @return [Array<String, Integer>] [host, port]
|
46
|
+
def get_host_port_from_uri(uri) #:nodoc:
|
47
|
+
uri_data = URI.split(uri)
|
48
|
+
[uri_data[2], uri_data[3]]
|
49
|
+
end
|
50
|
+
|
51
|
+
# call service
|
52
|
+
# @param [Message] srv_request srv Request instance
|
53
|
+
# @param [Message] srv_response srv Response instance
|
54
|
+
# @return [Boolean] result of call
|
55
|
+
def call(srv_request, srv_response)
|
56
|
+
if @persistent and @connection
|
57
|
+
# not connect
|
58
|
+
else
|
59
|
+
master = XMLRPC::Client.new2(@master_uri)
|
60
|
+
code, message, uri = master.call('lookupService',
|
61
|
+
@caller_id,
|
62
|
+
@service_name)
|
63
|
+
case code
|
64
|
+
when 1
|
65
|
+
host, port = get_host_port_from_uri(uri)
|
66
|
+
@connection = TCPROS::ServiceClient.new(host, port, @caller_id, @service_name, @service_type, @persistent)
|
67
|
+
return @connection.call(srv_request, srv_response)
|
68
|
+
when -1
|
69
|
+
raise "master error ${message}"
|
70
|
+
else
|
71
|
+
puts "fail to lookup"
|
72
|
+
nil
|
73
|
+
end
|
74
|
+
end
|
75
|
+
end
|
76
|
+
|
77
|
+
# shutdown this service client
|
78
|
+
def shutdown
|
79
|
+
@connection.close
|
80
|
+
end
|
81
|
+
|
82
|
+
end
|
83
|
+
end
|
@@ -0,0 +1,92 @@
|
|
1
|
+
# ros/service_server.rb
|
2
|
+
#
|
3
|
+
# License: BSD
|
4
|
+
#
|
5
|
+
# Copyright (C) 2012 Takashi Ogura <t.ogura@gmail.com>
|
6
|
+
#
|
7
|
+
# server of ROS Service.
|
8
|
+
# This uses ROS::TCPROS::ServiceServer for data transfer.
|
9
|
+
#
|
10
|
+
require 'ros/service'
|
11
|
+
require 'ros/tcpros/service_server'
|
12
|
+
|
13
|
+
module ROS
|
14
|
+
|
15
|
+
# server of ROS Service.
|
16
|
+
# {Node#advertise_service} return a instance of this class.
|
17
|
+
# Service can be shutdown by {ServiceServer#shutdown}.
|
18
|
+
# This class uses {TCPROS::ServiceServer} for data transfer.
|
19
|
+
# @example
|
20
|
+
# node = ROS::Node.new('/rosruby/sample_service_server')
|
21
|
+
# server = node.advertise_service('/add_two_ints', Roscpp_tutorials::TwoInts) do |req, res|
|
22
|
+
# res.sum = req.a + req.b
|
23
|
+
# node.loginfo("a=#{req.a}, b=#{req.b}")
|
24
|
+
# node.loginfo(" sum = #{res.sum}")
|
25
|
+
# true
|
26
|
+
# end
|
27
|
+
# while node.ok?
|
28
|
+
# sleep (1.0)
|
29
|
+
# end
|
30
|
+
class ServiceServer < Service
|
31
|
+
|
32
|
+
# @param [String] caller_id caller id of this node
|
33
|
+
# @param [String] service_name name of this service (String)
|
34
|
+
# @param [Class] service_type class of srv
|
35
|
+
# @param [Proc] callback callback object of this service.
|
36
|
+
def initialize(caller_id, service_name, service_type, callback)
|
37
|
+
super(caller_id, service_name, service_type)
|
38
|
+
@callback = callback
|
39
|
+
@server = TCPROS::ServiceServer.new(@caller_id,
|
40
|
+
@service_name,
|
41
|
+
@service_type,
|
42
|
+
self)
|
43
|
+
@server.start
|
44
|
+
@num_request = 0
|
45
|
+
end
|
46
|
+
|
47
|
+
##
|
48
|
+
# execute the service callback.
|
49
|
+
# User should not call this directly.
|
50
|
+
# @param [Message] request srv Request instance
|
51
|
+
# @param [Message] response srv Response instance
|
52
|
+
# @return [Boolean] callback result
|
53
|
+
def call(request, response)
|
54
|
+
@num_request += 1
|
55
|
+
@callback.call(request, response)
|
56
|
+
end
|
57
|
+
|
58
|
+
# URI of this service (rosrpc://**)
|
59
|
+
# @return [String] rosrpc service uri
|
60
|
+
def service_uri
|
61
|
+
'rosrpc://' + @server.host + ':' + @server.port.to_s
|
62
|
+
end
|
63
|
+
|
64
|
+
##
|
65
|
+
# user should not call this method.
|
66
|
+
# Please use shutdown method.
|
67
|
+
def close #:nodoc:
|
68
|
+
@server.shutdown
|
69
|
+
end
|
70
|
+
|
71
|
+
##
|
72
|
+
# shutdown the service connection
|
73
|
+
#
|
74
|
+
def shutdown
|
75
|
+
@manager.shutdow_service_server(self)
|
76
|
+
end
|
77
|
+
|
78
|
+
# set GraphManager for shutdown
|
79
|
+
# @param [GraphManager] manager set as manager
|
80
|
+
def set_manager(manager) #:nodoc:
|
81
|
+
@manager = manager
|
82
|
+
end
|
83
|
+
|
84
|
+
# @return [Array] connection data
|
85
|
+
def get_connection_data
|
86
|
+
[@num_request, @server.byte_received, @server.byte_sent]
|
87
|
+
end
|
88
|
+
|
89
|
+
# @return [Integer] how many times this service called
|
90
|
+
attr_reader :num_request
|
91
|
+
end
|
92
|
+
end
|
@@ -0,0 +1,153 @@
|
|
1
|
+
# ros/slave_proxy.rb
|
2
|
+
#
|
3
|
+
# License: BSD
|
4
|
+
#
|
5
|
+
# Copyright (C) 2012 Takashi Ogura <t.ogura@gmail.com>
|
6
|
+
#
|
7
|
+
#
|
8
|
+
# == ROS Slave Proxy
|
9
|
+
# you can access to ROS Slave nodes.
|
10
|
+
#
|
11
|
+
#
|
12
|
+
|
13
|
+
require 'xmlrpc/client'
|
14
|
+
|
15
|
+
module ROS
|
16
|
+
|
17
|
+
# you can access to ROS Slave nodes.
|
18
|
+
# @see http://ros.org/wiki/ROS/Slave_API
|
19
|
+
class SlaveProxy
|
20
|
+
|
21
|
+
# @param [String] caller_id caller id of this node
|
22
|
+
# @param [String] slave_uri URI to connect
|
23
|
+
def initialize(caller_id, slave_uri)
|
24
|
+
@caller_id = caller_id
|
25
|
+
@slave_uri = slave_uri
|
26
|
+
@proxy = XMLRPC::Client.new2(@slave_uri).proxy
|
27
|
+
end
|
28
|
+
|
29
|
+
# @return [Array] stats
|
30
|
+
# @raise [RuntimeError] if fail
|
31
|
+
def get_bus_stats
|
32
|
+
code, message, stats = @proxy.getBusStats(@caller_id)
|
33
|
+
if code == 1
|
34
|
+
return stats
|
35
|
+
else
|
36
|
+
raise message
|
37
|
+
end
|
38
|
+
end
|
39
|
+
|
40
|
+
# @return [Array] bus information
|
41
|
+
# @raise [RuntimeError] if fail
|
42
|
+
def get_bus_info
|
43
|
+
code, message, info = @proxy.getBusInfo(@caller_id)
|
44
|
+
if code == 1
|
45
|
+
return info
|
46
|
+
else
|
47
|
+
raise message
|
48
|
+
end
|
49
|
+
end
|
50
|
+
|
51
|
+
# @return [String] URI of master
|
52
|
+
# @raise [RuntimeError] if fail
|
53
|
+
def get_master_uri
|
54
|
+
code, message, uri = @proxy.getMasterUri(@caller_id)
|
55
|
+
if code == 1
|
56
|
+
return uri
|
57
|
+
else
|
58
|
+
raise message
|
59
|
+
end
|
60
|
+
end
|
61
|
+
|
62
|
+
# @param [String] msg message to slave (reason of shutdown request)
|
63
|
+
# @raise [RuntimeError] if fail
|
64
|
+
def shutdown(msg='')
|
65
|
+
code, message, val = @proxy.shutdown(@caller_id, msg)
|
66
|
+
if code == 1
|
67
|
+
return true
|
68
|
+
elsif code == 0
|
69
|
+
return false
|
70
|
+
else
|
71
|
+
raise message
|
72
|
+
end
|
73
|
+
end
|
74
|
+
|
75
|
+
# @return [Integer] pid of the slave process
|
76
|
+
# @raise [RuntimeError] if fail
|
77
|
+
def get_pid
|
78
|
+
code, message, pid = @proxy.getPid(@caller_id)
|
79
|
+
if code == 1
|
80
|
+
return pid
|
81
|
+
else
|
82
|
+
raise message
|
83
|
+
end
|
84
|
+
end
|
85
|
+
|
86
|
+
# @return [Array] topiccs
|
87
|
+
# @raise [RuntimeError] if fail
|
88
|
+
def get_subscriptions
|
89
|
+
code, message, topic = @proxy.getSubscriptions(@caller_id)
|
90
|
+
if code == 1
|
91
|
+
return topic
|
92
|
+
else
|
93
|
+
raise message
|
94
|
+
end
|
95
|
+
end
|
96
|
+
|
97
|
+
# @return [Array] publications
|
98
|
+
# @raise [RuntimeError] if fail
|
99
|
+
def get_publications
|
100
|
+
code, message, topic = @proxy.getPublications(@caller_id)
|
101
|
+
if code == 1
|
102
|
+
return topic
|
103
|
+
else
|
104
|
+
raise message
|
105
|
+
end
|
106
|
+
end
|
107
|
+
|
108
|
+
# @param [String] param_key key for param
|
109
|
+
# @param [String, Integer, Float, Boolean, Array] param_value new value for key
|
110
|
+
# @return [Boolean] true
|
111
|
+
# @raise [RuntimeError] if fail
|
112
|
+
def param_update(param_key, param_value)
|
113
|
+
code, message, val = @proxy.paramUpdate(@caller_id, param_key, param_value)
|
114
|
+
if code == 1
|
115
|
+
return true
|
116
|
+
else
|
117
|
+
raise message
|
118
|
+
end
|
119
|
+
end
|
120
|
+
|
121
|
+
# @param [String] topic name of topic
|
122
|
+
# @param [Array] publishers array of publisher uri
|
123
|
+
# @return [Boolean] true
|
124
|
+
# @raise [RuntimeError] if fail
|
125
|
+
def publisher_update(topic, publishers)
|
126
|
+
code, message, val = @proxy.publisherUpdate(@caller_id, topic, publishers)
|
127
|
+
if code == 1
|
128
|
+
return true
|
129
|
+
else
|
130
|
+
raise message
|
131
|
+
end
|
132
|
+
end
|
133
|
+
|
134
|
+
# @param [String] topic name of topic
|
135
|
+
#
|
136
|
+
def request_topic(topic, protocols)
|
137
|
+
code, message, protocol = @proxy.requestTopic(@caller_id,
|
138
|
+
topic,
|
139
|
+
protocols)
|
140
|
+
if code == 1
|
141
|
+
return protocol
|
142
|
+
else
|
143
|
+
raise message
|
144
|
+
end
|
145
|
+
end
|
146
|
+
|
147
|
+
# @return [String] URI of target
|
148
|
+
attr_accessor :slave_uri
|
149
|
+
|
150
|
+
# @return [String] caller_id of this caller
|
151
|
+
attr_accessor :caller_id
|
152
|
+
end
|
153
|
+
end
|
@@ -0,0 +1,119 @@
|
|
1
|
+
# ros/subscriber.rb
|
2
|
+
#
|
3
|
+
# License: BSD
|
4
|
+
#
|
5
|
+
# Copyright (C) 2012 Takashi Ogura <t.ogura@gmail.com>
|
6
|
+
#
|
7
|
+
require 'ros/topic'
|
8
|
+
require 'ros/tcpros/client'
|
9
|
+
require 'ros/slave_proxy'
|
10
|
+
|
11
|
+
module ROS
|
12
|
+
|
13
|
+
# subscriber of ROS topic. This is created by ROS::Node#subscribe.
|
14
|
+
# Please use proc block for callback method.
|
15
|
+
# It uses ROS::TCPROS::Client for message transfer.
|
16
|
+
# Subscription can be shutdown by this ROS::Subscriber#shutdown
|
17
|
+
# node = ROS::Node.new('/rosruby/sample_subscriber')
|
18
|
+
# sub = node.subscribe('/chatter', Std_msgs::String) do |msg|
|
19
|
+
# puts "message come! = \'#{msg.data}\'"
|
20
|
+
# end
|
21
|
+
# while node.ok?
|
22
|
+
# node.spin_once
|
23
|
+
# sleep(1)
|
24
|
+
# end
|
25
|
+
class Subscriber < Topic
|
26
|
+
|
27
|
+
# @param [String] caller_id caller id of this node
|
28
|
+
# @param [String] topic_name name of this topic (String)
|
29
|
+
# @param [Class] topic_type class of msg
|
30
|
+
# @param [Proc] callback callback for this topic
|
31
|
+
# @param [Boolean] tcp_no_delay use tcp no delay option or not
|
32
|
+
def initialize(caller_id, topic_name, topic_type, callback=nil, tcp_no_delay=nil)
|
33
|
+
super(caller_id, topic_name, topic_type)
|
34
|
+
@callback = callback
|
35
|
+
@tcp_no_delay = tcp_no_delay
|
36
|
+
end
|
37
|
+
|
38
|
+
# @return [Boolean] use tcp no delay option or not
|
39
|
+
attr_reader :tcp_no_delay
|
40
|
+
|
41
|
+
# @return [Proc] callback of this subscription
|
42
|
+
attr_reader :callback
|
43
|
+
|
44
|
+
##
|
45
|
+
# execute callback for all queued messages.
|
46
|
+
# This is called by {Node#spin_once}.
|
47
|
+
# It checks all queues of connections and callback for all messages.
|
48
|
+
def process_queue #:nodoc:
|
49
|
+
@connections.each do |connection|
|
50
|
+
while not connection.msg_queue.empty?
|
51
|
+
msg = connection.msg_queue.pop
|
52
|
+
if @callback
|
53
|
+
@callback.call(msg)
|
54
|
+
end
|
55
|
+
end
|
56
|
+
end
|
57
|
+
end
|
58
|
+
|
59
|
+
##
|
60
|
+
# request topic to master and start connection with publisher.
|
61
|
+
# @param [String] uri uri to connect
|
62
|
+
# @return [TCPROS::Client] new connection
|
63
|
+
def add_connection(uri) #:nodoc:
|
64
|
+
publisher = SlaveProxy.new(@caller_id, uri)
|
65
|
+
begin
|
66
|
+
protocol, host, port = publisher.request_topic(@topic_name, [["TCPROS"]])
|
67
|
+
if protocol == "TCPROS"
|
68
|
+
connection = TCPROS::Client.new(host, port, @caller_id, @topic_name, @topic_type, uri, @tcp_no_delay)
|
69
|
+
connection.start
|
70
|
+
else
|
71
|
+
puts "not support protocol: #{protocol}"
|
72
|
+
raise "not support protocol: #{protocol}"
|
73
|
+
end
|
74
|
+
connection.id = "#{@topic_name}_in_#{@connection_id_number}"
|
75
|
+
@connection_id_number += 1
|
76
|
+
@connections.push(connection)
|
77
|
+
return connection
|
78
|
+
rescue
|
79
|
+
puts "request fail"
|
80
|
+
return false
|
81
|
+
end
|
82
|
+
end
|
83
|
+
|
84
|
+
##
|
85
|
+
# data of connection. for slave API
|
86
|
+
# @return [Array] connection data
|
87
|
+
def get_connection_data
|
88
|
+
@connections.map do |connection|
|
89
|
+
[connection.id, connection.byte_received, 1]
|
90
|
+
end
|
91
|
+
end
|
92
|
+
|
93
|
+
##
|
94
|
+
# connection information fro slave API
|
95
|
+
# @return [Array] connection info
|
96
|
+
def get_connection_info
|
97
|
+
info = []
|
98
|
+
@connections.each do |connection|
|
99
|
+
info.push([connection.id, connection.target_uri, 'i', connection.protocol, @topic_name])
|
100
|
+
end
|
101
|
+
info
|
102
|
+
end
|
103
|
+
|
104
|
+
def has_connection_with?(uri)
|
105
|
+
get_connected_uri.include?(uri)
|
106
|
+
end
|
107
|
+
|
108
|
+
def get_connected_uri
|
109
|
+
@connections.map {|x| x.target_uri}
|
110
|
+
end
|
111
|
+
|
112
|
+
##
|
113
|
+
# user interface of shutdown this subscriber
|
114
|
+
#
|
115
|
+
def shutdown
|
116
|
+
@manager.shutdown_subscriber(self)
|
117
|
+
end
|
118
|
+
end
|
119
|
+
end
|