Class: Actionlib_tutorials::FibonacciAction

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/actionlib_tutorials/FibonacciAction.rb

Constant Summary collapse

@@struct_L3 =
::ROS::Struct.new("L3")
@@struct_C =
::ROS::Struct.new("C")
@@struct_L2 =
::ROS::Struct.new("L2")
@@struct_lL3 =
::ROS::Struct.new("lL3")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['actionlib_tutorials/FibonacciActionGoal','actionlib_tutorials/FibonacciActionResult','actionlib_tutorials/FibonacciActionFeedback']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ FibonacciAction

Constructor. You can set the default values using keyword operators.

Parameters:

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

    keyword for initializing values

Options Hash (args):



156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 156

def initialize(args={})
  # message fields cannot be None, assign default values for those that are
  if args[:action_goal]
    @action_goal = args[:action_goal]
  else
    @action_goal = Actionlib_tutorials::FibonacciActionGoal.new
  end
  if args[:action_result]
    @action_result = args[:action_result]
  else
    @action_result = Actionlib_tutorials::FibonacciActionResult.new
  end
  if args[:action_feedback]
    @action_feedback = args[:action_feedback]
  else
    @action_feedback = Actionlib_tutorials::FibonacciActionFeedback.new
  end
end

Instance Attribute Details

#action_feedbackObject

Returns the value of attribute action_feedback.



140
141
142
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 140

def action_feedback
  @action_feedback
end

#action_goalObject

Returns the value of attribute action_goal.



140
141
142
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 140

def action_goal
  @action_goal
end

#action_resultObject

Returns the value of attribute action_result.



140
141
142
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 140

def action_result
  @action_result
end

Class Method Details

.md5sumObject



18
19
20
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 18

def self.md5sum
  "f59df5767bf7634684781c92598b2406"
end

.typeObject



22
23
24
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 22

def self.type
  "actionlib_tutorials/FibonacciAction"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



177
178
179
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 177

def _get_types
  @slot_types
end

#deserialize(str) ⇒ Object

unpack serialized message in str into this message instance

@param [String] str: byte array of serialized message


233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 233

def deserialize(str)

  begin
    if @action_goal == nil
      @action_goal = Actionlib_tutorials::FibonacciActionGoal.new
    end
    if @action_result == nil
      @action_result = Actionlib_tutorials::FibonacciActionResult.new
    end
    if @action_feedback == nil
      @action_feedback = Actionlib_tutorials::FibonacciActionFeedback.new
    end
    end_point = 0
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@action_goal.header.seq, @action_goal.header.stamp.secs, @action_goal.header.stamp.nsecs,) = @@struct_L3.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_goal.header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2')
    (@action_goal.goal_id.stamp.secs, @action_goal.goal_id.stamp.nsecs,) = @@struct_L2.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_goal.goal_id.id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('lL3')
    (@action_goal.goal.order, @action_result.header.seq, @action_result.header.stamp.secs, @action_result.header.stamp.nsecs,) = @@struct_lL3.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_result.header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2')
    (@action_result.status.goal_id.stamp.secs, @action_result.status.goal_id.stamp.nsecs,) = @@struct_L2.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_result.status.goal_id.id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('C')
    (@action_result.status.status,) = @@struct_C.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_result.status.text = str[start..(end_point-1)]
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    pattern = "l#{length}"
    start = end_point
    end_point += ROS::Struct::calc_size("#{pattern}")
    @action_result.result.sequence = str[start..(end_point-1)].unpack(pattern)
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@action_feedback.header.seq, @action_feedback.header.stamp.secs, @action_feedback.header.stamp.nsecs,) = @@struct_L3.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_feedback.header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2')
    (@action_feedback.status.goal_id.stamp.secs, @action_feedback.status.goal_id.stamp.nsecs,) = @@struct_L2.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_feedback.status.goal_id.id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('C')
    (@action_feedback.status.status,) = @@struct_C.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @action_feedback.status.text = str[start..(end_point-1)]
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    pattern = "l#{length}"
    start = end_point
    end_point += ROS::Struct::calc_size("#{pattern}")
    @action_feedback.feedback.sequence = str[start..(end_point-1)].unpack(pattern)
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


26
27
28
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 26

def has_header?
  false
end

#message_definitionObject



30
31
32
33
34
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
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
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 30

def message_definition
  "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

FibonacciActionGoal action_goal
FibonacciActionResult action_result
FibonacciActionFeedback action_feedback

================================================================================
MSG: actionlib_tutorials/FibonacciActionGoal
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

Header header
actionlib_msgs/GoalID goal_id
FibonacciGoal goal

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data 
# in a particular coordinate frame.
# 
# sequence ID: consecutively increasing ID 
uint32 seq
#Two-integer timestamp that is expressed as:
# * stamp.secs: seconds (stamp_secs) since epoch
# * stamp.nsecs: nanoseconds since stamp_secs
# time-handling sugar is provided by the client library
time stamp
#Frame this data is associated with
# 0: no frame
# 1: global frame
string frame_id

================================================================================
MSG: actionlib_msgs/GoalID
# The stamp should store the time at which this goal was requested.
# It is used by an action server when it tries to preempt all
# goals that were requested before a certain time
time stamp

# The id provides a way to associate feedback and
# result message with specific goal requests. The id
# specified must be unique.
string id


================================================================================
MSG: actionlib_tutorials/FibonacciGoal
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
#goal definition
int32 order

================================================================================
MSG: actionlib_tutorials/FibonacciActionResult
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

Header header
actionlib_msgs/GoalStatus status
FibonacciResult result

================================================================================
MSG: actionlib_msgs/GoalStatus
GoalID goal_id
uint8 status
uint8 PENDING         = 0   # The goal has yet to be processed by the action server
uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
                          #   and has since completed its execution (Terminal State)
uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
                          #    to some failure (Terminal State)
uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
                          #    because the goal was unattainable or invalid (Terminal State)
uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
                          #    and has not yet completed execution
uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
                          #    but the action server has not yet confirmed that the goal is canceled
uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
                          #    and was successfully cancelled (Terminal State)
uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
                          #    sent over the wire by an action server

#Allow for the user to associate a string with GoalStatus for debugging
string text


================================================================================
MSG: actionlib_tutorials/FibonacciResult
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
#result definition
int32[] sequence

================================================================================
MSG: actionlib_tutorials/FibonacciActionFeedback
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

Header header
actionlib_msgs/GoalStatus status
FibonacciFeedback feedback

================================================================================
MSG: actionlib_tutorials/FibonacciFeedback
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
#feedback
int32[] sequence 



"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
# File 'lib/actionlib_tutorials/FibonacciAction.rb', line 183

def serialize(buff)
  begin
    buff.write(@@struct_L3.pack(@action_goal.header.seq, @action_goal.header.stamp.secs, @action_goal.header.stamp.nsecs))
    _x = @action_goal.header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2.pack(@action_goal.goal_id.stamp.secs, @action_goal.goal_id.stamp.nsecs))
    _x = @action_goal.goal_id.id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_lL3.pack(@action_goal.goal.order, @action_result.header.seq, @action_result.header.stamp.secs, @action_result.header.stamp.nsecs))
    _x = @action_result.header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2.pack(@action_result.status.goal_id.stamp.secs, @action_result.status.goal_id.stamp.nsecs))
    _x = @action_result.status.goal_id.id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_C.pack(@action_result.status.status))
    _x = @action_result.status.text
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    length = @action_result.result.sequence.length
    buff.write(@@struct_L.pack(length))
    pattern = "l#{length}"
    buff.write(*@action_result.result.sequence.pack(pattern))
    buff.write(@@struct_L3.pack(@action_feedback.header.seq, @action_feedback.header.stamp.secs, @action_feedback.header.stamp.nsecs))
    _x = @action_feedback.header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2.pack(@action_feedback.status.goal_id.stamp.secs, @action_feedback.status.goal_id.stamp.nsecs))
    _x = @action_feedback.status.goal_id.id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_C.pack(@action_feedback.status.status))
    _x = @action_feedback.status.text
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    length = @action_feedback.feedback.sequence.length
    buff.write(@@struct_L.pack(length))
    pattern = "l#{length}"
    buff.write(*@action_feedback.feedback.sequence.pack(pattern))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end