mavlink-log 0.0.1 → 0.0.2
Sign up to get free protection for your applications and to get access to all the features.
- checksums.yaml +4 -4
- data/README.md +1 -0
- data/lib/mavlink/log.rb +5 -1
- data/lib/mavlink/log/entry.rb +34 -0
- data/lib/mavlink/log/file.rb +16 -41
- data/lib/mavlink/log/header.rb +20 -0
- data/lib/mavlink/log/message.rb +83 -0
- data/lib/mavlink/log/messages/attitude.rb +37 -0
- data/lib/mavlink/log/messages/factory.rb +37 -0
- data/lib/mavlink/log/messages/global_position_int.rb +47 -0
- data/lib/mavlink/log/messages/gps_raw_int.rb +51 -0
- data/lib/mavlink/log/messages/heart_beat.rb +31 -0
- data/lib/mavlink/log/messages/messages.rb +15 -0
- data/lib/mavlink/log/messages/mission_current.rb +11 -0
- data/lib/mavlink/log/messages/nav_controller_output.rb +39 -0
- data/lib/mavlink/log/messages/param_request_list.rb +15 -0
- data/lib/mavlink/log/messages/param_value.rb +27 -0
- data/lib/mavlink/log/messages/raw_imu.rb +43 -0
- data/lib/mavlink/log/messages/rc_channels_raw.rb +47 -0
- data/lib/mavlink/log/messages/request_data_stream.rb +27 -0
- data/lib/mavlink/log/messages/scaled_pressure.rb +19 -0
- data/lib/mavlink/log/messages/servo_output_raw.rb +43 -0
- data/lib/mavlink/log/messages/sys_status.rb +64 -0
- data/lib/mavlink/log/messages/vfr_hud.rb +37 -0
- data/lib/mavlink/log/version.rb +1 -1
- data/spec/file_spec.rb +11 -1
- data/spec/messages/attitude_spec.rb +34 -0
- data/spec/messages/global_position_int_spec.rb +38 -0
- data/spec/messages/gps_raw_int_spec.rb +40 -0
- data/spec/messages/heart_beat_spec.rb +32 -0
- data/spec/messages/param_value_spec.rb +30 -0
- data/spec/messages/raw_imu_spec.rb +40 -0
- data/spec/messages/rc_channels_raw_spec.rb +42 -0
- data/spec/messages/sys_status_spec.rb +46 -0
- data/spec/messages/vfr_hud_spec.rb +32 -0
- data/spec/spec_helper.rb +2 -0
- data/spec/support/shared_examples_for_message.rb +13 -0
- data/spec/support/shared_examples_for_timed_message_micro.rb +9 -0
- data/spec/support/shared_examples_for_timed_message_milli.rb +9 -0
- data/spec/sys_status_spec.rb +0 -0
- metadata +48 -3
- data/lib/mavlink/log/messages.rb +0 -138
data/lib/mavlink/log/messages.rb
DELETED
@@ -1,138 +0,0 @@
|
|
1
|
-
module MAVLink
|
2
|
-
module Log
|
3
|
-
|
4
|
-
class Message
|
5
|
-
|
6
|
-
class << self
|
7
|
-
attr_accessor :id
|
8
|
-
end
|
9
|
-
|
10
|
-
end
|
11
|
-
|
12
|
-
class TimedMessage < Message
|
13
|
-
|
14
|
-
attr_accessor :time_boot_ms
|
15
|
-
|
16
|
-
def initialize(raw_payload)
|
17
|
-
@time_boot_ms = raw_payload[0..3].unpack('L<')[0]
|
18
|
-
end
|
19
|
-
|
20
|
-
end
|
21
|
-
|
22
|
-
class HeartBeat < Message
|
23
|
-
|
24
|
-
ID = 0
|
25
|
-
|
26
|
-
attr_accessor :type, :autopilot, :base_mode, :custom_mode, :system_status, :mavlink_version
|
27
|
-
|
28
|
-
def initialize(raw_payload)
|
29
|
-
@type = raw_payload[0].unpack('C')[0]
|
30
|
-
@autopilot = raw_payload[1].unpack('C')[0]
|
31
|
-
@base_mode = raw_payload[2].unpack('C')[0]
|
32
|
-
@custom_mode = raw_payload[3..6].unpack('L<')[0]
|
33
|
-
@system_status = raw_payload[7].unpack('C')[0]
|
34
|
-
@mavlink_version = raw_payload[8].unpack('C')[0]
|
35
|
-
end
|
36
|
-
|
37
|
-
end
|
38
|
-
|
39
|
-
class SysStatus < Message
|
40
|
-
|
41
|
-
ID = 1
|
42
|
-
|
43
|
-
attr_accessor :onboard_control_sensors_present, :onboard_control_sensors_enabled,
|
44
|
-
:onboard_control_sensors_health, :load, :voltage_battery, :current_battery,
|
45
|
-
:battery_remaining, :drop_rate_comm, :errors_comm,
|
46
|
-
:errors_count1, :errors_count2, :errors_count3, :errors_count4
|
47
|
-
|
48
|
-
def initialize(raw_payload)
|
49
|
-
@onboard_control_sensors_present = raw_payload[0..3].unpack('L<')[0] #
|
50
|
-
@onboard_control_sensors_enabled = raw_payload[4..7].unpack('L<')[0] #
|
51
|
-
@onboard_control_sensors_health = raw_payload[8..11].unpack('L<')[0] #
|
52
|
-
@load = raw_payload[12..13].unpack('S<')[0] / 10.0 # 0%..100%
|
53
|
-
@voltage_battery = raw_payload[14..15].unpack('S<')[0] / 1000.0 # V
|
54
|
-
@current_battery = raw_payload[16..17].unpack('s<')[0] / 100.0 # A (-1: not measured)
|
55
|
-
@battery_remaining = raw_payload[18].unpack('C')[0] # 0%..100% (-1: not measured)
|
56
|
-
@drop_rate_comm = raw_payload[19..20].unpack('S<')[0] / 100 # 0%..100% (bad packet %age)
|
57
|
-
@errors_comm = raw_payload[21..22].unpack('S<')[0] # bad packet count
|
58
|
-
@errors_count1 = raw_payload[23..24].unpack('S<')[0] #
|
59
|
-
@errors_count2 = raw_payload[25..26].unpack('S<')[0] #
|
60
|
-
@errors_count3 = raw_payload[27..28].unpack('S<')[0] #
|
61
|
-
@errors_count4 = raw_payload[29..30].unpack('S<')[0] #
|
62
|
-
end
|
63
|
-
|
64
|
-
end
|
65
|
-
|
66
|
-
class Attitude < TimedMessage
|
67
|
-
|
68
|
-
ID = 30
|
69
|
-
|
70
|
-
attr_accessor :roll, :pitch, :yaw, :rollspeed, :pitchspeed, :yawspeed
|
71
|
-
|
72
|
-
def initialize(raw_payload)
|
73
|
-
super
|
74
|
-
@roll = raw_payload[0..3].unpack('e')[0] # radians (-pi..pi)
|
75
|
-
@pitch = raw_payload[4..7].unpack('e')[0] # radians (-pi..pi)
|
76
|
-
@yaw = raw_payload[8..11].unpack('e')[0] # radians (-pi..pi)
|
77
|
-
@rollspeed = raw_payload[12..15].unpack('e')[0] # rad/s
|
78
|
-
@pitchspeed = raw_payload[16..19].unpack('e')[0] # rad/s
|
79
|
-
@yawspeed = raw_payload[20..23].unpack('e')[0] # rad/s
|
80
|
-
end
|
81
|
-
end
|
82
|
-
|
83
|
-
class GlobalPositionInt < TimedMessage
|
84
|
-
|
85
|
-
ID = 33
|
86
|
-
|
87
|
-
attr_accessor :lat, :lon, :alt, :relative_alt, :vx, :vy, :vz, :hdg
|
88
|
-
|
89
|
-
def initialize(raw_payload)
|
90
|
-
super
|
91
|
-
@lat = raw_payload[4..7].unpack('l<')[0] / 10000000.0 # dec. degrees
|
92
|
-
@lon = raw_payload[8..11].unpack('l<')[0] / 10000000.0 # dec. degrees
|
93
|
-
@alt = raw_payload[12..15].unpack('l<')[0] / 1000.0 # meters
|
94
|
-
@relative_alt = raw_payload[16..19].unpack('l<')[0] / 1000.0 # meters
|
95
|
-
@vx = raw_payload[20..21].unpack('s<')[0] / 100.0 # m/s
|
96
|
-
@vy = raw_payload[22..23].unpack('s<')[0] / 100.0 # m/s
|
97
|
-
@vz = raw_payload[24..25].unpack('s<')[0] / 100.0 # m/s
|
98
|
-
@hdg = raw_payload[26..27].unpack('S<')[0] / 100.0 # degrees (0.0..359.99) (0xFFFF if unknown)
|
99
|
-
end
|
100
|
-
|
101
|
-
end
|
102
|
-
|
103
|
-
class VfrHud < Message
|
104
|
-
|
105
|
-
ID = 74
|
106
|
-
|
107
|
-
attr_accessor :airspeed, :groundspeed, :heading, :throttle, :alt, :climb
|
108
|
-
|
109
|
-
def initialize(raw_payload)
|
110
|
-
@airspeed = raw_payload[0..3].unpack('e')[0] # m/s
|
111
|
-
@groundspeed = raw_payload[4..7].unpack('e')[0] # m/s
|
112
|
-
@heading = raw_payload[8..9].unpack('s<')[0] # degrees (0..360)
|
113
|
-
@throttle = raw_payload[10..11].unpack('S<')[0] # 0..100%
|
114
|
-
@alt = raw_payload[12..15].unpack('e')[0] # meters (MSL)
|
115
|
-
@climb = raw_payload[16..19].unpack('e')[0] # m/s
|
116
|
-
end
|
117
|
-
|
118
|
-
end
|
119
|
-
|
120
|
-
class MessageFactory
|
121
|
-
|
122
|
-
def self.build(entry)
|
123
|
-
case(entry.header.id)
|
124
|
-
when HeartBeat::ID; HeartBeat.new(entry.payload)
|
125
|
-
when SysStatus::ID; SysStatus.new(entry.payload)
|
126
|
-
when Attitude::ID; Attitude.new(entry.payload)
|
127
|
-
when GlobalPositionInt::ID; GlobalPositionInt.new(entry.payload)
|
128
|
-
when VfrHud::ID; VfrHud.new(entry.payload)
|
129
|
-
else
|
130
|
-
#puts entry.header.inspect
|
131
|
-
nil
|
132
|
-
end
|
133
|
-
end
|
134
|
-
|
135
|
-
end
|
136
|
-
|
137
|
-
end
|
138
|
-
end
|