JaiaBot 2.0.0
JaiaBot micro-AUV software
 
Loading...
Searching...
No Matches
imu.proto
Go to the documentation of this file.
1syntax = "proto2";
2
3import "dccl/option_extensions.proto";
4import "jaiabot/messages/mission.proto";
5
6package jaiabot.protobuf;
7
8message IMUCommand
9{
10 enum IMUCommandType
11 {
12 TAKE_READING = 0;
13 START_WAVE_HEIGHT_SAMPLING = 1;
14 STOP_WAVE_HEIGHT_SAMPLING = 2;
15 START_BOTTOM_TYPE_SAMPLING = 3;
16 STOP_BOTTOM_TYPE_SAMPLING = 4;
17 START_CALIBRATION = 5;
18 }
19
20 required IMUCommandType type = 1;
21}
22
23enum IMUCalibrationState
24{
25 IN_PROGRESS = 1;
26 COMPLETE = 2;
27}
28
29message IMUData
30{
31 message EulerAngles {
32 optional double heading = 1
33 [(dccl.field) = {units {
34 derived_dimensions: "plane_angle"
35 system: "angle::degree"
36 }}
37 ];
38
39 optional double pitch = 2
40 [(dccl.field) = {units {
41 derived_dimensions: "plane_angle"
42 system: "angle::degree"
43 }}
44 ];
45
46 optional double roll = 3
47 [(dccl.field) = {units {
48 derived_dimensions: "plane_angle"
49 system: "angle::degree"
50 }}
51 ];
52
53 }
54 optional EulerAngles euler_angles = 1;
55
56 message Acceleration {
57 optional double x = 1;
58 optional double y = 2;
59 optional double z = 3;
60 }
61
62 optional Acceleration linear_acceleration = 2;
63 optional Acceleration gravity = 3;
64
65 message Accuracies {
66 optional int32 accelerometer = 1 [(dccl.field) = { min: 0 max: 3 }];
67 optional int32 gyroscope = 2 [(dccl.field) = { min: 0 max: 3 }];
68 optional int32 magnetometer = 3 [(dccl.field) = { min: 0 max: 3 }];
69 }
70
71 optional Accuracies accuracies = 4;
72
73 optional IMUCalibrationState calibration_state = 5;
74
75 optional bool bot_rolled_over = 6 [default = false];
76
77 optional double significant_wave_height = 7 [(dccl.field) = {units {
78 derived_dimensions: "length"
79 system: "si"
80 }}
81 ];
82
83 // For bottom characterization
84 optional double max_acceleration = 8
85 [(dccl.field) = {units {
86 derived_dimensions: "acceleration"
87 system: "si"
88 }}
89 ];
90
91 message AngularVelocity {
92 optional double x = 1
93 [(dccl.field) = {
94 units {
95 derived_dimensions: "angular_velocity"
96 system: "si"
97 }
98 }];
99 optional double y = 2
100 [(dccl.field) = {
101 units {
102 derived_dimensions: "angular_velocity"
103 system: "si"
104 }
105 }];
106 optional double z = 3
107 [(dccl.field) = {
108 units {
109 derived_dimensions: "angular_velocity"
110 system: "si"
111 }
112 }];
113 }
114
115 optional AngularVelocity angular_velocity = 9;
116
117 message Quaternion {
118 optional double w = 1;
119 optional double x = 2;
120 optional double y = 3;
121 optional double z = 4;
122 }
123
124 optional Quaternion quaternion = 10;
125
126 optional string imu_type = 11;
127
128}
129
130message IMUIssue
131{
132 enum SolutionType
133 {
134 STOP_BOT = 0;
135 USE_COG = 1;
136 USE_CORRECTION = 2;
137 RESTART_BOT = 3;
138 REBOOT_BOT = 4;
139 REPORT_IMU = 5;
140 RESTART_IMU_PY = 6;
141 REBOOT_BNO085_IMU = 7;
142 REBOOT_BNO085_IMU_AND_RESTART_IMU_PY = 8;
143 }
144
145 required SolutionType solution = 1;
146
147 enum IssueType {
148 HEADING_COURSE_DIFFERENCE_TOO_LARGE = 0;
149 }
150
151 optional IssueType type = 2;
152
153 optional MissionState mission_state = 3;
154
155 optional double imu_heading_course_max_diff = 30 [default = 45];
156
157 optional double heading = 31 [(dccl.field) = {
158 min: 0
159 max: 360
160 precision: 0
161 units { derived_dimensions: "plane_angle" system: "angle::degree" }
162 }];
163
164 optional double desired_heading = 32 [(dccl.field) = {
165 min: 0
166 max: 360
167 precision: 0
168 units { derived_dimensions: "plane_angle" system: "angle::degree" }
169 }];
170
171 optional double course_over_ground = 33 [(dccl.field) = {
172 min: 0
173 max: 360
174 precision: 0
175 units { derived_dimensions: "plane_angle" system: "angle::degree" }
176 }];
177
178 optional double heading_course_difference = 34 [(dccl.field) = {
179 min: 0
180 max: 360
181 precision: 0
182 units { derived_dimensions: "plane_angle" system: "angle::degree" }
183 }];
184
185 optional double pitch = 35 [(dccl.field) = {
186 min: -180
187 max: 180
188 precision: 0
189 units { derived_dimensions: "plane_angle" system: "angle::degree" }
190 }];
191
192 optional double speed_over_ground = 36 [(dccl.field) = {
193 min: -5
194 max: 10
195 precision: 1
196 units { derived_dimensions: "velocity" system: "si" }
197 }];
198
199 optional double desired_speed = 37 [(dccl.field) = {
200 min: -5
201 max: 10
202 precision: 1
203 units { derived_dimensions: "velocity" system: "si" }
204 }];
205}