Class: Geometry_msgs::PoseWithCovarianceStamped

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/geometry_msgs/PoseWithCovarianceStamped.rb

Constant Summary collapse

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

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ PoseWithCovarianceStamped

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

  • :pose (geometry_msgs/PoseWithCovariance)

    initialize value



99
100
101
102
103
104
105
106
107
108
109
110
111
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 99

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[:pose]
    @pose = args[:pose]
  else
    @pose = Geometry_msgs::PoseWithCovariance.new
  end
end

Instance Attribute Details

#headerObject

Returns the value of attribute header.



85
86
87
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 85

def header
  @header
end

#poseObject

Returns the value of attribute pose.



85
86
87
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 85

def pose
  @pose
end

Class Method Details

.md5sumObject



13
14
15
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 13

def self.md5sum
  "953b798c0f514ff060a53a3498ce6246"
end

.typeObject



17
18
19
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 17

def self.type
  "geometry_msgs/PoseWithCovarianceStamped"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



115
116
117
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 115

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


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
164
165
166
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 137

def deserialize(str)

  begin
    if @header == nil
      @header = Std_msgs::Header.new
    end
    if @pose == nil
      @pose = Geometry_msgs::PoseWithCovariance.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 += 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)])
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


21
22
23
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 21

def has_header?
  true
end

#message_definitionObject



25
26
27
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
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 25

def message_definition
  "# This expresses an estimated pose with a reference coordinate frame and timestamp

Header header
PoseWithCovariance pose

================================================================================
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

"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



121
122
123
124
125
126
127
128
129
130
131
132
133
# File 'lib/geometry_msgs/PoseWithCovarianceStamped.rb', line 121

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}"))
    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))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end