Class: Sensor_msgs::Imu
- Inherits:
-
ROS::Message
- Object
- ROS::Message
- Sensor_msgs::Imu
- Defined in:
- lib/sensor_msgs/Imu.rb
Constant Summary collapse
- @@struct_L3 =
::ROS::Struct.new("L3")
- @@struct_d3 =
::ROS::Struct.new("d3")
- @@struct_d4 =
::ROS::Struct.new("d4")
- @@struct_d9 =
::ROS::Struct.new("d9")
- @@struct_L =
::ROS::Struct.new("L")
- @@slot_types =
['Header','geometry_msgs/Quaternion','float64[9]','geometry_msgs/Vector3','float64[9]','geometry_msgs/Vector3','float64[9]']
Instance Attribute Summary collapse
-
#angular_velocity ⇒ Object
Returns the value of attribute angular_velocity.
-
#angular_velocity_covariance ⇒ Object
Returns the value of attribute angular_velocity_covariance.
-
#header ⇒ Object
Returns the value of attribute header.
-
#linear_acceleration ⇒ Object
Returns the value of attribute linear_acceleration.
-
#linear_acceleration_covariance ⇒ Object
Returns the value of attribute linear_acceleration_covariance.
-
#orientation ⇒ Object
Returns the value of attribute orientation.
-
#orientation_covariance ⇒ Object
Returns the value of attribute orientation_covariance.
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 = {}) ⇒ Imu
constructor
Constructor.
- #message_definition ⇒ Object
-
#serialize(buff) ⇒ Object
serialize message into buffer.
Constructor Details
#initialize(args = {}) ⇒ Imu
Constructor. You can set the default values using keyword operators.
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 |
# File 'lib/sensor_msgs/Imu.rb', line 101 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[:orientation] @orientation = args[:orientation] else @orientation = Geometry_msgs::Quaternion.new end if args[:orientation_covariance] @orientation_covariance = args[:orientation_covariance] else @orientation_covariance = [0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0] end if args[:angular_velocity] @angular_velocity = args[:angular_velocity] else @angular_velocity = Geometry_msgs::Vector3.new end if args[:angular_velocity_covariance] @angular_velocity_covariance = args[:angular_velocity_covariance] else @angular_velocity_covariance = [0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0] end if args[:linear_acceleration] @linear_acceleration = args[:linear_acceleration] else @linear_acceleration = Geometry_msgs::Vector3.new end if args[:linear_acceleration_covariance] @linear_acceleration_covariance = args[:linear_acceleration_covariance] else @linear_acceleration_covariance = [0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0] end end |
Instance Attribute Details
#angular_velocity ⇒ Object
Returns the value of attribute angular_velocity.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def angular_velocity @angular_velocity end |
#angular_velocity_covariance ⇒ Object
Returns the value of attribute angular_velocity_covariance.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def angular_velocity_covariance @angular_velocity_covariance end |
#header ⇒ Object
Returns the value of attribute header.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def header @header end |
#linear_acceleration ⇒ Object
Returns the value of attribute linear_acceleration.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def linear_acceleration @linear_acceleration end |
#linear_acceleration_covariance ⇒ Object
Returns the value of attribute linear_acceleration_covariance.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def linear_acceleration_covariance @linear_acceleration_covariance end |
#orientation ⇒ Object
Returns the value of attribute orientation.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def orientation @orientation end |
#orientation_covariance ⇒ Object
Returns the value of attribute orientation_covariance.
81 82 83 |
# File 'lib/sensor_msgs/Imu.rb', line 81 def orientation_covariance @orientation_covariance end |
Class Method Details
.md5sum ⇒ Object
11 12 13 |
# File 'lib/sensor_msgs/Imu.rb', line 11 def self.md5sum "6a62c6daae103f4ff57a132d6f95cec2" end |
.type ⇒ Object
15 16 17 |
# File 'lib/sensor_msgs/Imu.rb', line 15 def self.type "sensor_msgs/Imu" end |
Instance Method Details
#_get_types ⇒ String
internal API method
142 143 144 |
# File 'lib/sensor_msgs/Imu.rb', line 142 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
168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 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 |
# File 'lib/sensor_msgs/Imu.rb', line 168 def deserialize(str) begin if @header == nil @header = Std_msgs::Header.new end if @orientation == nil @orientation = Geometry_msgs::Quaternion.new end if @angular_velocity == nil @angular_velocity = Geometry_msgs::Vector3.new end if @linear_acceleration == nil @linear_acceleration = Geometry_msgs::Vector3.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('d4') (@orientation.x, @orientation.y, @orientation.z, @orientation.w,) = @@struct_d4.unpack(str[start..(end_point-1)]) start = end_point end_point += 8 @orientation_covariance = @@struct_d9.unpack(str[start..(end_point-1)]) start = end_point end_point += ROS::Struct::calc_size('d3') (@angular_velocity.x, @angular_velocity.y, @angular_velocity.z,) = @@struct_d3.unpack(str[start..(end_point-1)]) start = end_point end_point += 8 @angular_velocity_covariance = @@struct_d9.unpack(str[start..(end_point-1)]) start = end_point end_point += ROS::Struct::calc_size('d3') (@linear_acceleration.x, @linear_acceleration.y, @linear_acceleration.z,) = @@struct_d3.unpack(str[start..(end_point-1)]) start = end_point end_point += 8 @linear_acceleration_covariance = @@struct_d9.unpack(str[start..(end_point-1)]) return self rescue => exception raise "message DeserializationError: #{exception}" #most likely buffer underfill end end |
#has_header? ⇒ Boolean
19 20 21 |
# File 'lib/sensor_msgs/Imu.rb', line 19 def has_header? true end |
#message_definition ⇒ Object
23 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 71 72 73 74 75 76 77 78 79 80 |
# File 'lib/sensor_msgs/Imu.rb', line 23 def "# This is a message to hold data from an IMU (Inertial Measurement Unit) # # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec # # If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal) # A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the data a covariance will have to be assumed or gotten from some other source # # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1 # If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate. Header header geometry_msgs/Quaternion orientation float64[9] orientation_covariance # Row major about x, y, z axes geometry_msgs/Vector3 angular_velocity float64[9] angular_velocity_covariance # Row major about x, y, z axes geometry_msgs/Vector3 linear_acceleration float64[9] linear_acceleration_covariance # Row major x, y z ================================================================================ 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/Quaternion # This represents an orientation in free space in quaternion form. float64 x float64 y float64 z float64 w ================================================================================ 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
148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 |
# File 'lib/sensor_msgs/Imu.rb', line 148 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_d4.pack(@orientation.x, @orientation.y, @orientation.z, @orientation.w)) buff.write(@@struct_d9.pack(*@orientation_covariance)) buff.write(@@struct_d3.pack(@angular_velocity.x, @angular_velocity.y, @angular_velocity.z)) buff.write(@@struct_d9.pack(*@angular_velocity_covariance)) buff.write(@@struct_d3.pack(@linear_acceleration.x, @linear_acceleration.y, @linear_acceleration.z)) buff.write(@@struct_d9.pack(*@linear_acceleration_covariance)) rescue => exception raise "some erro in serialize: #{exception}" end end |