Class: Geometry_msgs::PoseStamped
- Inherits:
-
ROS::Message
- Object
- ROS::Message
- Geometry_msgs::PoseStamped
- Defined in:
- lib/geometry_msgs/PoseStamped.rb
Constant Summary collapse
- @@struct_L3 =
::ROS::Struct.new("L3")
- @@struct_d7 =
::ROS::Struct.new("d7")
- @@struct_L =
::ROS::Struct.new("L")
- @@slot_types =
['Header','geometry_msgs/Pose']
Instance Attribute Summary collapse
-
#header ⇒ Object
Returns the value of attribute header.
-
#pose ⇒ Object
Returns the value of attribute pose.
Class Method Summary collapse
Instance Method Summary collapse
-
#_get_types ⇒ String
internal API method.
-
#deserialize(str) ⇒ Object
unpack serialized message in str into this message instance @param [String] str: byte array of serialized message.
- #has_header? ⇒ Boolean
-
#initialize(args = {}) ⇒ PoseStamped
constructor
Constructor.
- #message_definition ⇒ Object
-
#serialize(buff) ⇒ Object
serialize message into buffer.
Constructor Details
#initialize(args = {}) ⇒ PoseStamped
Constructor. You can set the default values using keyword operators.
84 85 86 87 88 89 90 91 92 93 94 95 96 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 84 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::Pose.new end end |
Instance Attribute Details
#header ⇒ Object
Returns the value of attribute header.
71 72 73 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 71 def header @header end |
#pose ⇒ Object
Returns the value of attribute pose.
71 72 73 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 71 def pose @pose end |
Class Method Details
.md5sum ⇒ Object
12 13 14 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 12 def self.md5sum "d3812c3cbc69362b77dc0b19b345f8f5" end |
.type ⇒ Object
16 17 18 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 16 def self.type "geometry_msgs/PoseStamped" end |
Instance Method Details
#_get_types ⇒ String
internal API method
100 101 102 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 100 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
121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 121 def deserialize(str) begin if @header == nil @header = Std_msgs::Header.new end if @pose == nil @pose = Geometry_msgs::Pose.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.position.x, @pose.position.y, @pose.position.z, @pose.orientation.x, @pose.orientation.y, @pose.orientation.z, @pose.orientation.w,) = @@struct_d7.unpack(str[start..(end_point-1)]) return self rescue => exception raise "message DeserializationError: #{exception}" #most likely buffer underfill end end |
#has_header? ⇒ Boolean
20 21 22 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 20 def has_header? true end |
#message_definition ⇒ Object
24 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 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 24 def "# A Pose with reference coordinate frame and timestamp Header header Pose 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/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
106 107 108 109 110 111 112 113 114 115 116 117 |
# File 'lib/geometry_msgs/PoseStamped.rb', line 106 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.position.x, @pose.position.y, @pose.position.z, @pose.orientation.x, @pose.orientation.y, @pose.orientation.z, @pose.orientation.w)) rescue => exception raise "some erro in serialize: #{exception}" end end |