Class: Nav_msgs::Odometry

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/nav_msgs/Odometry.rb

Constant Summary collapse

@@struct_L3 =
::ROS::Struct.new("L3")
@@struct_d7 =
::ROS::Struct.new("d7")
@@struct_d6 =
::ROS::Struct.new("d6")
@@struct_d36 =
::ROS::Struct.new("d36")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['Header','string','geometry_msgs/PoseWithCovariance','geometry_msgs/TwistWithCovariance']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ Odometry

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

Parameters:

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

    keyword for initializing values

Options Hash (args):

  • :header (Header)

    initialize value

  • :child_frame_id (string)

    initialize value

  • :pose (geometry_msgs/PoseWithCovariance)

    initialize value

  • :twist (geometry_msgs/TwistWithCovariance)

    initialize value



133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
# File 'lib/nav_msgs/Odometry.rb', line 133

def initialize(args={})
  # message fields cannot be None, assign default values for those that are
  if args[:header]
    @header = args[:header]
  else
    @header = Std_msgs::Header.new
  end
  if args[:child_frame_id]
    @child_frame_id = args[:child_frame_id]
  else
    @child_frame_id = ''
  end
  if args[:pose]
    @pose = args[:pose]
  else
    @pose = Geometry_msgs::PoseWithCovariance.new
  end
  if args[:twist]
    @twist = args[:twist]
  else
    @twist = Geometry_msgs::TwistWithCovariance.new
  end
end

Instance Attribute Details

#child_frame_idObject

Returns the value of attribute child_frame_id.



116
117
118
# File 'lib/nav_msgs/Odometry.rb', line 116

def child_frame_id
  @child_frame_id
end

#headerObject

Returns the value of attribute header.



116
117
118
# File 'lib/nav_msgs/Odometry.rb', line 116

def header
  @header
end

#poseObject

Returns the value of attribute pose.



116
117
118
# File 'lib/nav_msgs/Odometry.rb', line 116

def pose
  @pose
end

#twistObject

Returns the value of attribute twist.



116
117
118
# File 'lib/nav_msgs/Odometry.rb', line 116

def twist
  @twist
end

Class Method Details

.md5sumObject



16
17
18
# File 'lib/nav_msgs/Odometry.rb', line 16

def self.md5sum
  "cd5e73d190d741a2f92e81eda573aca7"
end

.typeObject



20
21
22
# File 'lib/nav_msgs/Odometry.rb', line 20

def self.type
  "nav_msgs/Odometry"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



159
160
161
# File 'lib/nav_msgs/Odometry.rb', line 159

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


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
230
# File 'lib/nav_msgs/Odometry.rb', line 186

def deserialize(str)

  begin
    if @header == nil
      @header = Std_msgs::Header.new
    end
    if @pose == nil
      @pose = Geometry_msgs::PoseWithCovariance.new
    end
    if @twist == nil
      @twist = Geometry_msgs::TwistWithCovariance.new
    end
    end_point = 0
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@header.seq, @header.stamp.secs, @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
    @header.frame_id = 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
    @child_frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('d7')
    (@pose.pose.position.x, @pose.pose.position.y, @pose.pose.position.z, @pose.pose.orientation.x, @pose.pose.orientation.y, @pose.pose.orientation.z, @pose.pose.orientation.w,) = @@struct_d7.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 8
    @pose.covariance = @@struct_d36.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += ROS::Struct::calc_size('d6')
    (@twist.twist.linear.x, @twist.twist.linear.y, @twist.twist.linear.z, @twist.twist.angular.x, @twist.twist.angular.y, @twist.twist.angular.z,) = @@struct_d6.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 8
    @twist.covariance = @@struct_d36.unpack(str[start..(end_point-1)])
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


24
25
26
# File 'lib/nav_msgs/Odometry.rb', line 24

def has_header?
  true
end

#message_definitionObject



28
29
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
# File 'lib/nav_msgs/Odometry.rb', line 28

def message_definition
  "# This represents an estimate of a position and velocity in free space.  
# The pose in this message should be specified in the coordinate frame given by header.frame_id.
# The twist in this message should be specified in the coordinate frame given by the child_frame_id
Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist

================================================================================
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: geometry_msgs/PoseWithCovariance
# This represents a pose in free space with uncertainty.

Pose pose

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance

================================================================================
MSG: geometry_msgs/Pose
# A representation of pose in free space, composed of postion and orientation. 
Point position
Quaternion orientation

================================================================================
MSG: geometry_msgs/Point
# This contains the position of a point in free space
float64 x
float64 y
float64 z

================================================================================
MSG: geometry_msgs/Quaternion
# This represents an orientation in free space in quaternion form.

float64 x
float64 y
float64 z
float64 w

================================================================================
MSG: geometry_msgs/TwistWithCovariance
# This expresses velocity in free space with uncertianty.

Twist twist

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance

================================================================================
MSG: geometry_msgs/Twist
# This expresses velocity in free space broken into it's linear and angular parts. 
Vector3  linear
Vector3  angular

================================================================================
MSG: geometry_msgs/Vector3
# This represents a vector in free space. 

float64 x
float64 y
float64 z
"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
# File 'lib/nav_msgs/Odometry.rb', line 165

def serialize(buff)
  begin
    buff.write(@@struct_L3.pack(@header.seq, @header.stamp.secs, @header.stamp.nsecs))
    _x = @header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    _x = @child_frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_d7.pack(@pose.pose.position.x, @pose.pose.position.y, @pose.pose.position.z, @pose.pose.orientation.x, @pose.pose.orientation.y, @pose.pose.orientation.z, @pose.pose.orientation.w))
    buff.write(@@struct_d36.pack(*@pose.covariance))
    buff.write(@@struct_d6.pack(@twist.twist.linear.x, @twist.twist.linear.y, @twist.twist.linear.z, @twist.twist.angular.x, @twist.twist.angular.y, @twist.twist.angular.z))
    buff.write(@@struct_d36.pack(*@twist.covariance))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end