Class: Player::Client

Inherits:
Device
  • Object
show all
Includes:
Common
Defined in:
lib/ruby-player/client.rb

Overview

The client object manages the connection with the Player server

Examples:


require 'ruby-player'
Player::Client.connect("localhost") do |robot|
  pos2d = robot.subscribe("position2d", index: 0)
  pos2d.set_speed(vx: 1, vy: 0, va: 0.2)
  #main loop
  robot.loop do
    puts "Position: x=%{px}, y=%{py}, a=%{pa}" % pos2d.state
  end
end

Instance Attribute Summary collapse

Attributes inherited from Device

#addr

Instance Method Summary collapse

Methods inherited from Device

#fill, #send_message

Constructor Details

#initialize(host, opts = {}) ⇒ Client

Initialize client

Parameters:

  • host (String)

    host of Player server

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

    client options

Options Hash (opts):

  • :port (Object)

    port of connection

  • :log_level (Object)

    level of log messages [:debug, :info, :warn, :error] default :info



41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
# File 'lib/ruby-player/client.rb', line 41

def initialize(host, opts = {})
  port = opts[:port] || 6665
  @log_level = (opts[:log_level] || :info).to_sym

  @socket = TCPSocket.new(host, port)
  @addr = DevAddr.new(host: 0, robot: 0, interface: PLAYER_PLAYER_CODE, index: 0)
  @client = self
  @devices = []

  banner = @socket.read(PLAYER_IDENT_STRLEN)
  info "Connect with #{banner} in #{host}:#{port}"
  warn "This software required Player version >= 3.1.0" if banner[/\d.\d/].to_f < 3.1
  send_message PLAYER_MSGTYPE_REQ, PLAYER_PLAYER_REQ_DATAMODE, [PLAYER_DATAMODE_PULL].pack("N")

  debug "Set delivery mode in PULL"

  if block_given?
    yield self
    close
  else
    self
  end
end

Dynamic Method Handling

This class handles dynamic methods through the method_missing method

#method_missing(name, *args) ⇒ Object (private)



223
224
225
226
227
228
229
# File 'lib/ruby-player/client.rb', line 223

def method_missing(name, *args)
  if Player.constants.include?("PLAYER_#{name.to_s.upcase}_CODE".to_sym)
    subscribe(name, index:args[0], access:args[1])
  else
    super
  end
end

Instance Attribute Details

#log_levelObject (readonly)

Returns the value of attribute log_level.



34
35
36
# File 'lib/ruby-player/client.rb', line 34

def log_level
  @log_level
end

Instance Method Details

#closeObject

Close connection



106
107
108
# File 'lib/ruby-player/client.rb', line 106

def close
  @socket.close
end

#closed?Boolean

Check connection

Returns:

  • (Boolean)


101
102
103
# File 'lib/ruby-player/client.rb', line 101

def closed?
  @socket.closed?
end

#handle_response(hdr, msg) ⇒ Object



132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
# File 'lib/ruby-player/client.rb', line 132

def handle_response(hdr, msg)
  case hdr.subtype
  when 0
    nil
  when PLAYER_PLAYER_REQ_DEV
    # read device identifier
    dev_addr = DevAddr.decode(msg[0,PLAYERXDR_DEVADDR_SIZE])
    # read the granted access and driver name
    data = msg[PLAYERXDR_DEVADDR_SIZE,8].unpack("NN")
    access = data[0]
    # read driver name
    drv_name = msg[-data[1]-3..-1]

    if access == PLAYER_ERROR_MODE
      raise_error "Error subscribing to " + dev_addr.interface_name + ":" + dev_addr.index 
    end
    
    debug "Got response: #{dev_addr.interface_name}:#{dev_addr.index} (driver name - #{drv_name})"

    @dev = make_device(dev_addr)
    if @devices.one? { |d| d.addr == dev_addr }
      warn "The device #{dev_addr.interface_name}:#{dev_addr.index} has already been subscribed" 
      @dev = nil 
    else 
      @devices << @dev
    end
  when PLAYER_PLAYER_REQ_DATAMODE, PLAYER_PLAYER_REQ_DATA
    nil
  else
    warn "Don't implement ACK for subtype = #{hdr.subtype}"  
  end
end

#loop(period = 1.0) ⇒ Object

Loop for control code

Examples:

cl.loop(0.5) do
  #...you control code
end

Parameters:

  • period (defaults to: 1.0)

    period cicles in seconds



118
119
120
121
122
123
124
# File 'lib/ruby-player/client.rb', line 118

def loop(period=1.0)
  while(true) do
    read!
    yield
    sleep(period.to_f)
  end
end

#read!Object

Read data from server and update all subscribed proxy objects



70
71
72
73
74
75
# File 'lib/ruby-player/client.rb', line 70

def read!
  send_message PLAYER_MSGTYPE_REQ, PLAYER_PLAYER_REQ_DATA, ""
  while read[0].type != PLAYER_MSGTYPE_SYNCH
  end
  nil
end

#send_message_with_hdr(hdr, msg) ⇒ Object



126
127
128
129
130
# File 'lib/ruby-player/client.rb', line 126

def send_message_with_hdr(hdr, msg)
  send_header hdr
  @socket.write msg 
  @socket.flush
end

#subscribe(type, opts = {}) ⇒ Object

Get proxy object

Examples:

pos2d = client.subscribe(:position2d, index: 0)

Parameters:

  • type (String, Symbol)

    interface type name

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

    of subscribing

Options Hash (opts):

  • :index (Object)

    index of device (default 0)

  • :access (Object)

    access level (default PLAYER_OPEN_MODE)



86
87
88
89
90
91
92
93
94
95
96
97
98
# File 'lib/ruby-player/client.rb', line 86

def subscribe(type, opts = {})
  code = instance_eval("PLAYER_#{type.to_s.upcase}_CODE")
  index = opts[:index] || 0
  access = opts[:access] || PLAYER_OPEN_MODE

  info "Subscribing to #{type}:#{index}"
  data = DevAddr.new(interface: code, index: index).to_a + [access, 0, 0]
  send_message PLAYER_MSGTYPE_REQ, PLAYER_PLAYER_REQ_DEV, data.pack("N*")

  read!
  
  @dev
end