spatial_packets.c
Go to the documentation of this file.
1 /****************************************************************/
2 /* */
3 /* Advanced Navigation Packet Protocol Library */
4 /* C Language Dynamic Spatial SDK, Version 4.0 */
5 /* Copyright 2014, Xavier Orr, Advanced Navigation Pty Ltd */
6 /* */
7 /****************************************************************/
8 /*
9  * Copyright (C) 2014 Advanced Navigation Pty Ltd
10  *
11  * Permission is hereby granted, free of charge, to any person obtaining
12  * a copy of this software and associated documentation files (the "Software"),
13  * to deal in the Software without restriction, including without limitation
14  * the rights to use, copy, modify, merge, publish, distribute, sublicense,
15  * and/or sell copies of the Software, and to permit persons to whom the
16  * Software is furnished to do so, subject to the following conditions:
17  *
18  * The above copyright notice and this permission notice shall be included
19  * in all copies or substantial portions of the Software.
20  *
21  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
22  * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
23  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
24  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
25  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
26  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
27  * DEALINGS IN THE SOFTWARE.
28  */
29 
30  #include <stdint.h>
31  #include <string.h>
32  #include "an_packet_protocol.h"
33  #include "spatial_packets.h"
34 
35 /*
36  * This file contains functions to decode and encode packets
37  *
38  * Decode functions take an an_packet_t and turn it into a type specific
39  * to that packet so that the fields can be conveniently accessed. Decode
40  * functions return 0 for success and 1 for failure. Decode functions are
41  * used when receiving packets.
42  *
43  * Example decode
44  *
45  * an_packet_t an_packet
46  * acknowledge_packet_t acknowledge_packet
47  * ...
48  * decode_acknowledge_packet(&acknowledge_packet, &an_packet);
49  * printf("acknowledge id %d with result %d\n", acknowledge_packet.packet_id, acknowledge_packet.acknowledge_result);
50  *
51  * Encode functions take a type specific structure and turn it into an
52  * an_packet_t. Encode functions are used when sending packets. Don't
53  * forget to free the returned packet with an_packet_free().
54  *
55  * Example encode
56  *
57  * an_packet_t *an_packet;
58  * boot_mode_packet_t boot_mode_packet;
59  * ...
60  * boot_mode_packet.boot_mode = boot_mode_bootloader;
61  * an_packet = encode_boot_mode_packet(&boot_mode_packet);
62  * serial_port_transmit(an_packet_pointer(an_packet), an_packet_size(an_packet));
63  * an_packet_free(&an_packet);
64  *
65  */
66 
67 int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet)
68 {
69  if(an_packet->id == packet_id_acknowledge && an_packet->length == 4)
70  {
71  acknowledge_packet->packet_id = an_packet->data[0];
72  memcpy(&acknowledge_packet->packet_crc, &an_packet->data[1], sizeof(uint16_t));
73  acknowledge_packet->acknowledge_result = an_packet->data[3];
74  return 0;
75  }
76  else return 1;
77 }
78 
79 an_packet_t *encode_request_packet(uint8_t requested_packet_id)
80 {
82  an_packet->data[0] = requested_packet_id;
83  return an_packet;
84 }
85 
86 int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet)
87 {
88  if(an_packet->id == packet_id_boot_mode && an_packet->length == 1)
89  {
90  boot_mode_packet->boot_mode = an_packet->data[0];
91  return 0;
92  }
93  else return 1;
94 }
95 
97 {
99  an_packet->data[0] = boot_mode_packet->boot_mode;
100  return an_packet;
101 }
102 
104 {
105  if(an_packet->id == packet_id_device_information && an_packet->length == 24)
106  {
107  memcpy(&device_information_packet->software_version, &an_packet->data[0], sizeof(uint32_t));
108  memcpy(&device_information_packet->device_id, &an_packet->data[4], sizeof(uint32_t));
109  memcpy(&device_information_packet->hardware_revision, &an_packet->data[8], sizeof(uint32_t));
110  memcpy(&device_information_packet->serial_number[0], &an_packet->data[12], 3*sizeof(uint32_t));
111  return 0;
112  }
113  else return 1;
114 }
115 
117 {
118  uint32_t verification = 0x85429E1C;
120  memcpy(&an_packet->data[0], &verification, sizeof(uint32_t));
121  return an_packet;
122 }
123 
125 {
126  uint32_t verification = 0x21057A7E;
128  memcpy(&an_packet->data[0], &verification, sizeof(uint32_t));
129  return an_packet;
130 }
131 
133 {
134  if(an_packet->id == packet_id_file_transfer_acknowledge && an_packet->length == 9)
135  {
136  memcpy(&file_transfer_acknowledge_packet->unique_id, &an_packet->data[0], sizeof(uint32_t));
137  memcpy(&file_transfer_acknowledge_packet->data_index, &an_packet->data[4], sizeof(uint32_t));
138  file_transfer_acknowledge_packet->response_code = an_packet->data[8];
139  return 0;
140  }
141  else return 1;
142 }
143 
144 int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet)
145 {
146  if(an_packet->id == packet_id_system_state && an_packet->length == 100)
147  {
148  memcpy(&system_state_packet->system_status, &an_packet->data[0], sizeof(uint16_t));
149  memcpy(&system_state_packet->filter_status, &an_packet->data[2], sizeof(uint16_t));
150  memcpy(&system_state_packet->unix_time_seconds, &an_packet->data[4], sizeof(uint32_t));
151  memcpy(&system_state_packet->microseconds, &an_packet->data[8], sizeof(uint32_t));
152  memcpy(&system_state_packet->latitude, &an_packet->data[12], sizeof(double));
153  memcpy(&system_state_packet->longitude, &an_packet->data[20], sizeof(double));
154  memcpy(&system_state_packet->height, &an_packet->data[28], sizeof(double));
155  memcpy(&system_state_packet->velocity[0], &an_packet->data[36], 3 * sizeof(float));
156  memcpy(&system_state_packet->body_acceleration[0], &an_packet->data[48], 3 * sizeof(float));
157  memcpy(&system_state_packet->g_force, &an_packet->data[60], sizeof(float));
158  memcpy(&system_state_packet->orientation[0], &an_packet->data[64], 3 * sizeof(float));
159  memcpy(&system_state_packet->angular_velocity[0], &an_packet->data[76], 3 * sizeof(float));
160  memcpy(&system_state_packet->standard_deviation[0], &an_packet->data[88], 3 * sizeof(float));
161  return 0;
162  }
163  else return 1;
164 }
165 
166 int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet)
167 {
168  if(an_packet->id == packet_id_unix_time && an_packet->length == 8)
169  {
170  memcpy(&unix_time_packet->unix_time_seconds, &an_packet->data[0], sizeof(uint32_t));
171  memcpy(&unix_time_packet->microseconds, &an_packet->data[4], sizeof(uint32_t));
172  return 0;
173  }
174  else return 1;
175 }
176 
177 int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet)
178 {
179  if(an_packet->id == packet_id_formatted_time && an_packet->length == 14)
180  {
181  memcpy(&formatted_time_packet->microseconds, &an_packet->data[0], sizeof(uint32_t));
182  memcpy(&formatted_time_packet->year, &an_packet->data[4], sizeof(uint16_t));
183  memcpy(&formatted_time_packet->year_day, &an_packet->data[6], sizeof(uint16_t));
184  formatted_time_packet->month = an_packet->data[8];
185  formatted_time_packet->month_day = an_packet->data[9];
186  formatted_time_packet->week_day = an_packet->data[10];
187  formatted_time_packet->hour = an_packet->data[11];
188  formatted_time_packet->minute = an_packet->data[12];
189  formatted_time_packet->second = an_packet->data[13];
190  return 0;
191  }
192  else return 1;
193 }
194 
195 int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet)
196 {
197  if(an_packet->id == packet_id_status && an_packet->length == 4)
198  {
199  memcpy(&status_packet->system_status, &an_packet->data[0], sizeof(uint16_t));
200  memcpy(&status_packet->filter_status, &an_packet->data[2], sizeof(uint16_t));
201  return 0;
202  }
203  else return 1;
204 }
205 
207 {
208  if(an_packet->id == packet_id_position_standard_deviation && an_packet->length == 12)
209  {
210  memcpy(&position_standard_deviation_packet->standard_deviation[0], &an_packet->data[0], 3*sizeof(float));
211  return 0;
212  }
213  else return 1;
214 }
215 
217 {
218  if(an_packet->id == packet_id_velocity_standard_deviation && an_packet->length == 12)
219  {
220  memcpy(&velocity_standard_deviation_packet->standard_deviation[0], &an_packet->data[0], 3*sizeof(float));
221  return 0;
222  }
223  else return 1;
224 }
225 
227 {
228  if(an_packet->id == packet_id_euler_orientation_standard_deviation && an_packet->length == 12)
229  {
230  memcpy(&euler_orientation_standard_deviation->standard_deviation[0], &an_packet->data[0], 3*sizeof(float));
231  return 0;
232  }
233  else return 1;
234 }
235 
237 {
238  if(an_packet->id == packet_id_quaternion_orientation_standard_deviation && an_packet->length == 16)
239  {
240  memcpy(&quaternion_orientation_standard_deviation_packet->standard_deviation[0], &an_packet->data[0], 4*sizeof(float));
241  return 0;
242  }
243  else return 1;
244 }
245 
246 int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet)
247 {
248  if(an_packet->id == packet_id_raw_sensors && an_packet->length == 48)
249  {
250  memcpy(&raw_sensors_packet->accelerometers[0], &an_packet->data[0], 3 * sizeof(float));
251  memcpy(&raw_sensors_packet->gyroscopes[0], &an_packet->data[12], 3 * sizeof(float));
252  memcpy(&raw_sensors_packet->magnetometers[0], &an_packet->data[24], 3 * sizeof(float));
253  memcpy(&raw_sensors_packet->imu_temperature, &an_packet->data[36], sizeof(float));
254  memcpy(&raw_sensors_packet->pressure, &an_packet->data[40], sizeof(float));
255  memcpy(&raw_sensors_packet->pressure_temperature, &an_packet->data[44], sizeof(float));
256  return 0;
257  }
258  else return 1;
259 }
260 
261 int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet)
262 {
263  if(an_packet->id == packet_id_raw_gnss && an_packet->length == 74)
264  {
265  memcpy(&raw_gnss_packet->unix_time_seconds, &an_packet->data[0], sizeof(uint32_t));
266  memcpy(&raw_gnss_packet->microseconds, &an_packet->data[4], sizeof(uint32_t));
267  memcpy(&raw_gnss_packet->position[0], &an_packet->data[8], 3*sizeof(double));
268  memcpy(&raw_gnss_packet->velocity[0], &an_packet->data[32], 3*sizeof(float));
269  memcpy(&raw_gnss_packet->position_standard_deviation[0], &an_packet->data[44], 3*sizeof(float));
270  memcpy(&raw_gnss_packet->tilt, &an_packet->data[56], sizeof(float));
271  memcpy(&raw_gnss_packet->heading, &an_packet->data[60], sizeof(float));
272  memcpy(&raw_gnss_packet->tilt_standard_deviation, &an_packet->data[64], sizeof(float));
273  memcpy(&raw_gnss_packet->heading_standard_deviation, &an_packet->data[68], sizeof(float));
274  memcpy(&raw_gnss_packet->flags.r, &an_packet->data[72], sizeof(uint16_t));
275  return 0;
276  }
277  else return 1;
278 }
279 
280 int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet)
281 {
282  if(an_packet->id == packet_id_satellites && an_packet->length == 13)
283  {
284  memcpy(&satellites_packet->hdop, &an_packet->data[0], sizeof(float));
285  memcpy(&satellites_packet->vdop, &an_packet->data[4], sizeof(float));
286  memcpy(&satellites_packet->gps_satellites, &an_packet->data[8], 5*sizeof(uint8_t));
287  return 0;
288  }
289  else return 1;
290 }
291 
293 {
294  if(an_packet->id == packet_id_satellites_detailed && (an_packet->length % 7) == 0)
295  {
296  int number_of_satellites = an_packet->length / 7;
297  int i;
298  for(i = 0; i < MAXIMUM_DETAILED_SATELLITES; i++)
299  {
300  if(i < number_of_satellites)
301  {
302  detailed_satellites_packet->satellites[i].satellite_system = an_packet->data[7*i];
303  detailed_satellites_packet->satellites[i].number = an_packet->data[7*i + 1];
304  detailed_satellites_packet->satellites[i].frequencies.r = an_packet->data[7*i + 2];
305  detailed_satellites_packet->satellites[i].elevation = an_packet->data[7*i + 3];
306  memcpy(&detailed_satellites_packet->satellites[i].azimuth, &an_packet->data[7*i + 4], sizeof(uint16_t));
307  detailed_satellites_packet->satellites[i].snr = an_packet->data[7*i + 6];
308  }
309  else memset(&detailed_satellites_packet->satellites[i], 0, sizeof(satellite_t));
310  }
311  return 0;
312  }
313  else return 1;
314 }
315 
317 {
318  if(an_packet->id == packet_id_geodetic_position && an_packet->length == 24)
319  {
320  memcpy(&geodetic_position_packet->position[0], &an_packet->data[0], 3*sizeof(double));
321  return 0;
322  }
323  else return 1;
324 }
325 
326 int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet)
327 {
328  if(an_packet->id == packet_id_ecef_position && an_packet->length == 24)
329  {
330  memcpy(&ecef_position_packet->position[0], &an_packet->data[0], 3*sizeof(double));
331  return 0;
332  }
333  else return 1;
334 }
335 
336 int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet)
337 {
338  if(an_packet->id == packet_id_utm_position && an_packet->length == 25)
339  {
340  memcpy(&utm_position_packet->position, &an_packet->data[0], 3*sizeof(double));
341  utm_position_packet->zone = an_packet->data[24];
342  return 0;
343  }
344  else return 1;
345 }
346 
347 int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet)
348 {
349  if(an_packet->id == packet_id_ned_velocity && an_packet->length == 12)
350  {
351  memcpy(&ned_velocity_packet->velocity, &an_packet->data[0], 3*sizeof(float));
352  return 0;
353  }
354  else return 1;
355 }
356 
357 int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet)
358 {
359  if(an_packet->id == packet_id_body_velocity && an_packet->length == 12)
360  {
361  memcpy(&body_velocity_packet->velocity, &an_packet->data[0], 3*sizeof(float));
362  return 0;
363  }
364  else return 1;
365 }
366 
368 {
369  if(an_packet->id == packet_id_acceleration && an_packet->length == 12)
370  {
371  memcpy(&acceleration->acceleration[0], &an_packet->data[0], 3*sizeof(float));
372  return 0;
373  }
374  else return 1;
375 }
376 
378 {
379  if(an_packet->id == packet_id_body_acceleration && an_packet->length == 16)
380  {
381  memcpy(&body_acceleration->acceleration[0], &an_packet->data[0], 3*sizeof(float));
382  memcpy(&body_acceleration->g_force, &an_packet->data[12], sizeof(float));
383  return 0;
384  }
385  else return 1;
386 }
387 
389 {
390  if(an_packet->id == packet_id_euler_orientation && an_packet->length == 12)
391  {
392  memcpy(&euler_orientation_packet->orientation[0], &an_packet->data[0], 3*sizeof(float));
393  return 0;
394  }
395  else return 1;
396 }
397 
399 {
400  if(an_packet->id == packet_id_quaternion_orientation && an_packet->length == 16)
401  {
402  memcpy(&quaternion_orientation_packet->orientation[0], &an_packet->data[0], 4*sizeof(float));
403  return 0;
404  }
405  else return 1;
406 }
407 
409 {
410  if(an_packet->id == packet_id_dcm_orientation && an_packet->length == 36)
411  {
412  memcpy(&dcm_orientation_packet->orientation[0][0], &an_packet->data[0], 9*sizeof(float));
413  return 0;
414  }
415  else return 1;
416 }
417 
419 {
420  if(an_packet->id == packet_id_angular_velocity && an_packet->length == 12)
421  {
422  memcpy(&angular_velocity_packet->angular_velocity[0], &an_packet->data[0], 3*sizeof(float));
423  return 0;
424  }
425  else return 1;
426 }
427 
429 {
430  if(an_packet->id == packet_id_angular_acceleration && an_packet->length == 12)
431  {
432  memcpy(&angular_acceleration_packet->angular_acceleration[0], &an_packet->data[0], 3*sizeof(float));
433  return 0;
434  }
435  else return 1;
436 }
437 
439 {
440  if(an_packet->id == packet_id_external_position_velocity && an_packet->length == 60)
441  {
442  memcpy(&external_position_velocity_packet->position[0], &an_packet->data[0], 3*sizeof(double));
443  memcpy(&external_position_velocity_packet->velocity[0], &an_packet->data[24], 3*sizeof(float));
444  memcpy(&external_position_velocity_packet->position_standard_deviation[0], &an_packet->data[36], 3*sizeof(float));
445  memcpy(&external_position_velocity_packet->velocity_standard_deviation[0], &an_packet->data[48], 3*sizeof(float));
446  return 0;
447  }
448  else return 1;
449 }
450 
452 {
454  if(an_packet != NULL)
455  {
456  memcpy(&an_packet->data[0], &external_position_velocity_packet->position[0], 3*sizeof(double));
457  memcpy(&an_packet->data[24], &external_position_velocity_packet->velocity[0], 3*sizeof(float));
458  memcpy(&an_packet->data[36], &external_position_velocity_packet->position_standard_deviation[0], 3*sizeof(float));
459  memcpy(&an_packet->data[48], &external_position_velocity_packet->velocity_standard_deviation[0], 3*sizeof(float));
460  }
461  return an_packet;
462 }
463 
465 {
466  if(an_packet->id == packet_id_external_position && an_packet->length == 36)
467  {
468  memcpy(&external_position_packet->position[0], &an_packet->data[0], 3*sizeof(double));
469  memcpy(&external_position_packet->standard_deviation[0], &an_packet->data[24], 3*sizeof(float));
470  return 0;
471  }
472  else return 1;
473 }
474 
476 {
478  if(an_packet != NULL)
479  {
480  memcpy(&an_packet->data[0], &external_position_packet->position[0], 3*sizeof(double));
481  memcpy(&an_packet->data[24], &external_position_packet->standard_deviation[0], 3*sizeof(float));
482  }
483  return an_packet;
484 }
485 
487 {
488  if(an_packet->id == packet_id_external_velocity && an_packet->length == 24)
489  {
490  memcpy(&external_velocity_packet->velocity[0], &an_packet->data[0], 3*sizeof(float));
491  memcpy(&external_velocity_packet->standard_deviation[0], &an_packet->data[12], 3*sizeof(float));
492  return 0;
493  }
494  else return 1;
495 }
496 
498 {
500  if(an_packet != NULL)
501  {
502  memcpy(&an_packet->data[0], &external_velocity_packet->velocity[0], 3*sizeof(float));
503  memcpy(&an_packet->data[12], &external_velocity_packet->standard_deviation[0], 3*sizeof(float));
504  }
505  return an_packet;
506 }
507 
509 {
510  if(an_packet->id == packet_id_external_body_velocity && an_packet->length == 16)
511  {
512  memcpy(&external_body_velocity_packet->velocity, &an_packet->data[0], 3*sizeof(float));
513  memcpy(&external_body_velocity_packet->standard_deviation, &an_packet->data[12], sizeof(float));
514  return 0;
515  }
516  else return 1;
517 }
518 
520 {
522  if(an_packet != NULL)
523  {
524  memcpy(&an_packet->data[0], &external_body_velocity_packet->velocity[0], 3*sizeof(float));
525  memcpy(&an_packet->data[12], &external_body_velocity_packet->standard_deviation, sizeof(float));
526  }
527  return an_packet;
528 }
529 
531 {
532  if(an_packet->id == packet_id_external_heading && an_packet->length == 8)
533  {
534  memcpy(&external_heading_packet->heading, &an_packet->data[0], sizeof(float));
535  memcpy(&external_heading_packet->standard_deviation, &an_packet->data[4], sizeof(float));
536  return 0;
537  }
538  else return 1;
539 }
540 
542 {
544  if(an_packet != NULL)
545  {
546  memcpy(&an_packet->data[0], &external_heading_packet->heading, sizeof(float));
547  memcpy(&an_packet->data[4], &external_heading_packet->standard_deviation, sizeof(float));
548  }
549  return an_packet;
550 }
551 
552 int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet)
553 {
554  if(an_packet->id == packet_id_running_time && an_packet->length == 8)
555  {
556  memcpy(&running_time_packet->seconds, &an_packet->data[0], sizeof(uint32_t));
557  memcpy(&running_time_packet->microseconds, &an_packet->data[4], sizeof(uint32_t));
558  return 0;
559  }
560  else return 1;
561 }
562 
564 {
565  if(an_packet->id == packet_id_local_magnetics && an_packet->length == 12)
566  {
567  memcpy(&local_magnetics_packet->magnetic_field[0], &an_packet->data[0], 3*sizeof(float));
568  return 0;
569  }
570  else return 1;
571 }
572 
573 int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet)
574 {
575  if(an_packet->id == packet_id_odometer_state && an_packet->length == 20)
576  {
577  memcpy(&odometer_state_packet->pulse_count, &an_packet->data[0], sizeof(uint32_t));
578  memcpy(&odometer_state_packet->distance, &an_packet->data[4], sizeof(float));
579  memcpy(&odometer_state_packet->speed, &an_packet->data[8], sizeof(float));
580  memcpy(&odometer_state_packet->slip, &an_packet->data[12], sizeof(float));
581  odometer_state_packet->active = an_packet->data[16];
582  return 0;
583  }
584  else return 1;
585 }
586 
587 int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet)
588 {
589  if(an_packet->id == packet_id_external_time && an_packet->length == 8)
590  {
591  memcpy(&external_time_packet->unix_time_seconds, &an_packet->data[0], sizeof(float));
592  memcpy(&external_time_packet->microseconds, &an_packet->data[4], sizeof(float));
593  return 0;
594  }
595  else return 1;
596 }
597 
599 {
601  if(an_packet != NULL)
602  {
603  memcpy(&an_packet->data[0], &external_time_packet->unix_time_seconds, sizeof(float));
604  memcpy(&an_packet->data[4], &external_time_packet->microseconds, sizeof(float));
605  }
606  return an_packet;
607 }
608 
609 int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet)
610 {
611  if(an_packet->id == packet_id_external_depth && an_packet->length == 8)
612  {
613  memcpy(&external_depth_packet->depth, &an_packet->data[0], sizeof(float));
614  memcpy(&external_depth_packet->standard_deviation, &an_packet->data[4], sizeof(float));
615  return 0;
616  }
617  else return 1;
618 }
619 
621 {
623  if(an_packet != NULL)
624  {
625  memcpy(&an_packet->data[0], &external_depth_packet->depth, sizeof(float));
626  memcpy(&an_packet->data[4], &external_depth_packet->standard_deviation, sizeof(float));
627  }
628  return an_packet;
629 }
630 
631 int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet)
632 {
633  if(an_packet->id == packet_id_geoid_height && an_packet->length == 4)
634  {
635  memcpy(&geoid_height_packet->geoid_height, &an_packet->data[0], sizeof(float));
636  return 0;
637  }
638  else return 1;
639 }
640 
642 {
643  if(an_packet->id == packet_id_external_pitot_pressure && an_packet->length == 8)
644  {
645  memcpy(&external_pitot_pressure_packet->differential_pressure, &an_packet->data[0], sizeof(float));
646  memcpy(&external_pitot_pressure_packet->outside_air_temperature, &an_packet->data[4], sizeof(float));
647  return 0;
648  }
649  else return 1;
650 }
651 
653 {
655  if(an_packet != NULL)
656  {
657  memcpy(&an_packet->data[0], &external_pitot_pressure_packet->differential_pressure, sizeof(float));
658  memcpy(&an_packet->data[4], &external_pitot_pressure_packet->outside_air_temperature, sizeof(float));
659  }
660  return an_packet;
661 }
662 
663 int decode_wind_packet(wind_packet_t *wind_packet, an_packet_t *an_packet)
664 {
665  if(an_packet->id == packet_id_wind && an_packet->length == 12)
666  {
667  memcpy(&wind_packet->wind_velocity[0], &an_packet->data[0], 2*sizeof(float));
668  memcpy(&wind_packet->wind_standard_deviation, &an_packet->data[8], sizeof(float));
669  return 0;
670  }
671  else return 1;
672 }
673 
675 {
677  if(an_packet != NULL)
678  {
679  memcpy(&an_packet->data[0], &wind_packet->wind_velocity[0], 2*sizeof(float));
680  memcpy(&an_packet->data[8], &wind_packet->wind_standard_deviation, sizeof(float));
681  }
682  return an_packet;
683 }
684 
685 int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet)
686 {
687  if(an_packet->id == packet_id_heave && an_packet->length == 16)
688  {
689  memcpy(&heave_packet->heave_point_1, &an_packet->data[0], sizeof(float));
690  memcpy(&heave_packet->heave_point_2, &an_packet->data[4], sizeof(float));
691  memcpy(&heave_packet->heave_point_3, &an_packet->data[8], sizeof(float));
692  memcpy(&heave_packet->heave_point_4, &an_packet->data[12], sizeof(float));
693  return 0;
694  }
695  else return 1;
696 }
697 
698 int decode_odometer_packet(odometer_packet_t *external_odometer_packet, an_packet_t *an_packet)
699 {
700  if(an_packet->id == packet_id_external_odometer && an_packet->length == 13)
701  {
702  memcpy(&external_odometer_packet->delay, &an_packet->data[0], sizeof(float));
703  memcpy(&external_odometer_packet->speed, &an_packet->data[4], sizeof(float));
704  memcpy(&external_odometer_packet->distance_travelled, &an_packet->data[8], sizeof(float));
705  external_odometer_packet->flags.r = an_packet->data[12];
706  return 0;
707  }
708  else return 1;
709 }
710 
712 {
714  if(an_packet != NULL)
715  {
716  memcpy(&an_packet->data[0], &external_odometer_packet->delay, sizeof(float));
717  memcpy(&an_packet->data[4], &external_odometer_packet->speed, sizeof(float));
718  memcpy(&an_packet->data[8], &external_odometer_packet->distance_travelled, sizeof(float));
719  an_packet->data[12] = external_odometer_packet->flags.r;
720  }
721  return an_packet;
722 }
723 
725 {
726  if(an_packet->id == packet_id_external_air_data && an_packet->length == 25)
727  {
728  memcpy(&external_air_data_packet->altitude_delay, &an_packet->data[0], sizeof(float));
729  memcpy(&external_air_data_packet->airspeed_delay, &an_packet->data[4], sizeof(float));
730  memcpy(&external_air_data_packet->altitude, &an_packet->data[8], sizeof(float));
731  memcpy(&external_air_data_packet->airspeed, &an_packet->data[12], sizeof(float));
732  memcpy(&external_air_data_packet->altitude_standard_deviation, &an_packet->data[16], sizeof(float));
733  memcpy(&external_air_data_packet->airspeed_standard_deviation, &an_packet->data[20], sizeof(float));
734  external_air_data_packet->flags.r = an_packet->data[24];
735  return 0;
736  }
737  else return 1;
738 }
739 
741 {
743  if(an_packet != NULL)
744  {
745  memcpy(&an_packet->data[0], &external_air_data_packet->altitude_delay, sizeof(float));
746  memcpy(&an_packet->data[4], &external_air_data_packet->airspeed_delay, sizeof(float));
747  memcpy(&an_packet->data[8], &external_air_data_packet->altitude, sizeof(float));
748  memcpy(&an_packet->data[12], &external_air_data_packet->airspeed, sizeof(float));
749  memcpy(&an_packet->data[16], &external_air_data_packet->altitude_standard_deviation, sizeof(float));
750  memcpy(&an_packet->data[20], &external_air_data_packet->airspeed_standard_deviation, sizeof(float));
751  an_packet->data[24] = external_air_data_packet->flags.r;
752  }
753  return an_packet;
754 }
755 
756 /* Start of configuration packet functions */
757 
759 {
760  if(an_packet->id == packet_id_packet_timer_period && an_packet->length == 4)
761  {
762  packet_timer_period_packet->permanent = an_packet->data[0];
763  packet_timer_period_packet->utc_synchronisation = an_packet->data[1];
764  memcpy(&packet_timer_period_packet->packet_timer_period, &an_packet->data[2], sizeof(uint16_t));
765  return 0;
766  }
767  else return 1;
768 }
769 
771 {
773  if(an_packet != NULL)
774  {
775  an_packet->data[0] = packet_timer_period_packet->permanent > 0;
776  an_packet->data[1] = packet_timer_period_packet->utc_synchronisation > 0;
777  memcpy(&an_packet->data[2], &packet_timer_period_packet->packet_timer_period, sizeof(uint16_t));
778  }
779  return an_packet;
780 }
781 
782 int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet)
783 {
784  if(an_packet->id == packet_id_packet_periods && (an_packet->length - 2) % 5 == 0)
785  {
786  int i;
787  int packet_periods_count = (an_packet->length - 2) / 5;
788  packet_periods_packet->permanent = an_packet->data[0];
789  packet_periods_packet->clear_existing_packets = an_packet->data[1];
790  for(i = 0; i < MAXIMUM_PACKET_PERIODS; i++)
791  {
792  if(i < packet_periods_count)
793  {
794  packet_periods_packet->packet_periods[i].packet_id = an_packet->data[2 + 5*i];
795  memcpy(&packet_periods_packet->packet_periods[i].period, &an_packet->data[2 + 5*i + 1], sizeof(uint32_t));
796  }
797  else memset(&packet_periods_packet->packet_periods[i], 0, sizeof(packet_period_t));
798  }
799  return 0;
800  }
801  else return 1;
802 }
803 
805 {
806  int i;
808  if(an_packet != NULL)
809  {
810  an_packet->data[0] = packet_periods_packet->permanent > 0;
811  an_packet->data[1] = packet_periods_packet->clear_existing_packets;
812  for(i = 0; i < MAXIMUM_PACKET_PERIODS; i++)
813  {
814  if(packet_periods_packet->packet_periods[i].packet_id)
815  {
816  an_packet->data[2 + 5*i] = packet_periods_packet->packet_periods[i].packet_id;
817  memcpy(&an_packet->data[2 + 5*i + 1], &packet_periods_packet->packet_periods[i].period, sizeof(uint32_t));
818  }
819  else break;
820  }
821  an_packet->length = 2 + 5*i;
822  }
823  return an_packet;
824 }
825 
826 int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet)
827 {
828  if(an_packet->id == packet_id_baud_rates && an_packet->length == 17)
829  {
830  baud_rates_packet->permanent = an_packet->data[0];
831  memcpy(&baud_rates_packet->primary_baud_rate, &an_packet->data[1], sizeof(uint32_t));
832  memcpy(&baud_rates_packet->gpio_1_2_baud_rate, &an_packet->data[5], sizeof(uint32_t));
833  memcpy(&baud_rates_packet->auxiliary_baud_rate, &an_packet->data[9], sizeof(uint32_t));
834  memcpy(&baud_rates_packet->reserved, &an_packet->data[13], sizeof(uint32_t));
835  return 0;
836  }
837  else return 1;
838 }
839 
841 {
843  if(an_packet != NULL)
844  {
845  an_packet->data[0] = baud_rates_packet->permanent;
846  memcpy(&an_packet->data[1], &baud_rates_packet->primary_baud_rate, sizeof(uint32_t));
847  memcpy(&an_packet->data[5], &baud_rates_packet->gpio_1_2_baud_rate, sizeof(uint32_t));
848  memcpy(&an_packet->data[9], &baud_rates_packet->auxiliary_baud_rate, sizeof(uint32_t));
849  memcpy(&an_packet->data[13], &baud_rates_packet->reserved, sizeof(uint32_t));
850  }
851  return an_packet;
852 }
853 
854 int decode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet, an_packet_t *an_packet)
855 {
856  if(an_packet->id == packet_id_sensor_ranges && an_packet->length == 4)
857  {
858  memcpy(sensor_ranges_packet, an_packet->data, 4*sizeof(uint8_t));
859  return 0;
860  }
861  else return 1;
862 }
863 
865 {
867  if(an_packet != NULL)
868  {
869  memcpy(an_packet->data, sensor_ranges_packet, 4*sizeof(uint8_t));
870  }
871  return an_packet;
872 }
873 
875 {
876  if(an_packet->id == packet_id_installation_alignment && an_packet->length == 73)
877  {
878  installation_alignment_packet->permanent = an_packet->data[0];
879  memcpy(&installation_alignment_packet->alignment_dcm[0][0], &an_packet->data[1], 9*sizeof(float));
880  memcpy(&installation_alignment_packet->gnss_antenna_offset[0], &an_packet->data[37], 3*sizeof(float));
881  memcpy(&installation_alignment_packet->odometer_offset[0], &an_packet->data[49], 3*sizeof(float));
882  memcpy(&installation_alignment_packet->external_data_offset[0], &an_packet->data[61], 3*sizeof(float));
883  return 0;
884  }
885  else return 1;
886 }
887 
889 {
891  if(an_packet != NULL)
892  {
893  an_packet->data[0] = installation_alignment_packet->permanent;
894  memcpy(&an_packet->data[1], &installation_alignment_packet->alignment_dcm[0][0], 9*sizeof(float));
895  memcpy(&an_packet->data[37], &installation_alignment_packet->gnss_antenna_offset[0], 3*sizeof(float));
896  memcpy(&an_packet->data[49], &installation_alignment_packet->odometer_offset[0], 3*sizeof(float));
897  memcpy(&an_packet->data[61], &installation_alignment_packet->external_data_offset[0], 3*sizeof(float));
898  }
899  return an_packet;
900 }
901 
902 int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet)
903 {
904  if(an_packet->id == packet_id_filter_options && an_packet->length == 17)
905  {
906  memcpy(filter_options_packet, &an_packet->data[0], 9*sizeof(uint8_t));
907  return 0;
908  }
909  else return 1;
910 }
911 
913 {
915  if(an_packet != NULL)
916  {
917  memcpy(&an_packet->data[0], filter_options_packet, 9*sizeof(uint8_t));
918  memset(&an_packet->data[9], 0, 8*sizeof(uint8_t));
919  }
920  return an_packet;
921 }
922 
924 {
925  if(an_packet->id == packet_id_gpio_configuration && an_packet->length == 13)
926  {
927  memcpy(gpio_configuration_packet, &an_packet->data[0], 5*sizeof(uint8_t));
928  return 0;
929  }
930  else return 1;
931 }
932 
934 {
936  if(an_packet != NULL)
937  {
938  memcpy(&an_packet->data[0], gpio_configuration_packet, 5*sizeof(uint8_t));
939  memset(&an_packet->data[5], 0, 8*sizeof(uint8_t));
940  }
941  return an_packet;
942 }
943 
945 {
946  if(an_packet->id == packet_id_magnetic_calibration_values && an_packet->length == 49)
947  {
948  magnetic_calibration_values_packet->permanent = an_packet->data[0];
949  memcpy(magnetic_calibration_values_packet->hard_iron, &an_packet->data[5], 3*sizeof(float));
950  memcpy(magnetic_calibration_values_packet->soft_iron, &an_packet->data[13], 9*sizeof(float));
951  return 0;
952  }
953  else return 1;
954 }
955 
957 {
959  if(an_packet != NULL)
960  {
961  an_packet->data[0] = magnetic_calibration_values_packet->permanent;
962  memcpy(&an_packet->data[1], magnetic_calibration_values_packet->hard_iron, 3*sizeof(float));
963  memcpy(&an_packet->data[13], magnetic_calibration_values_packet->soft_iron, 9*sizeof(float));
964  }
965  return an_packet;
966 }
967 
969 {
971  if(an_packet != NULL)
972  {
973  an_packet->data[0] = magnetic_calibration_configuration_packet->magnetic_calibration_action;
974  }
975  return an_packet;
976 }
977 
979 {
980  if(an_packet->id == packet_id_magnetic_calibration_status && an_packet->length == 3)
981  {
982  magnetic_calibration_status_packet->magnetic_calibration_status = an_packet->data[0];
983  magnetic_calibration_status_packet->magnetic_calibration_progress_percentage = an_packet->data[1];
984  magnetic_calibration_status_packet->local_magnetic_error_percentage = an_packet->data[2];
985  return 0;
986  }
987  return 1;
988 }
989 
991 {
992  if(an_packet->id == packet_id_odometer_configuration && an_packet->length == 8)
993  {
994  odometer_configuration_packet->permanent = an_packet->data[0];
995  odometer_configuration_packet->automatic_calibration = an_packet->data[1];
996  memcpy(&odometer_configuration_packet->pulse_length, &an_packet->data[4], sizeof(float));
997  return 0;
998  }
999  else return 1;
1000 }
1001 
1003 {
1005  if(an_packet != NULL)
1006  {
1007  an_packet->data[0] = odometer_configuration_packet->permanent;
1008  an_packet->data[1] = odometer_configuration_packet->automatic_calibration;
1009  memset(&an_packet->data[2], 0, 2*sizeof(uint8_t));
1010  memcpy(&an_packet->data[4], &odometer_configuration_packet->pulse_length, sizeof(float));
1011  }
1012  return an_packet;
1013 }
1014 
1016 {
1017  uint32_t verification = 0x9A4E8055;
1019  if(an_packet != NULL)
1020  {
1021  an_packet->data[0] = zero_alignment_packet->permanent;
1022  memcpy(&an_packet->data[1], &verification, sizeof(uint32_t));
1023  }
1024  return an_packet;
1025 }
1026 
1027 int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet)
1028 {
1029  if(an_packet->id == packet_id_heave_offset && an_packet->length == 49)
1030  {
1031  heave_offset_packet->permanent = an_packet->data[0];
1032  memcpy(&heave_offset_packet->heave_point_1_offset[0], &an_packet->data[1], 3*sizeof(float));
1033  memcpy(&heave_offset_packet->heave_point_2_offset[0], &an_packet->data[13], 3*sizeof(float));
1034  memcpy(&heave_offset_packet->heave_point_3_offset[0], &an_packet->data[25], 3*sizeof(float));
1035  memcpy(&heave_offset_packet->heave_point_4_offset[0], &an_packet->data[37], 3*sizeof(float));
1036  return 0;
1037  }
1038  else return 1;
1039 }
1040 
1042 {
1044  if(an_packet != NULL)
1045  {
1046  an_packet->data[0] = heave_offset_packet->permanent;
1047  memcpy(&an_packet->data[1], &heave_offset_packet->heave_point_1_offset[0], 3*sizeof(float));
1048  memcpy(&an_packet->data[13], &heave_offset_packet->heave_point_2_offset[0], 3*sizeof(float));
1049  memcpy(&an_packet->data[25], &heave_offset_packet->heave_point_3_offset[0], 3*sizeof(float));
1050  memcpy(&an_packet->data[37], &heave_offset_packet->heave_point_4_offset[0], 3*sizeof(float));
1051  }
1052  return an_packet;
1053 }
1054 
1056 {
1057  if(an_packet->id == packet_id_gpio_output_configuration && an_packet->length == 33)
1058  {
1059  gpio_output_configuration_packet->permanent = an_packet->data[0];
1060  gpio_output_configuration_packet->nmea_fix_behaviour = an_packet->data[1];
1061  memcpy(&gpio_output_configuration_packet->gpzda_rate.r, &an_packet->data[2], sizeof(uint16_t));
1062  memcpy(&gpio_output_configuration_packet->gpgga_rate.r, &an_packet->data[4], sizeof(uint16_t));
1063  memcpy(&gpio_output_configuration_packet->gpvtg_rate.r, &an_packet->data[6], sizeof(uint16_t));
1064  memcpy(&gpio_output_configuration_packet->gprmc_rate.r, &an_packet->data[8], sizeof(uint16_t));
1065  memcpy(&gpio_output_configuration_packet->gphdt_rate.r, &an_packet->data[10], sizeof(uint16_t));
1066  memcpy(&gpio_output_configuration_packet->gpgll_rate.r, &an_packet->data[12], sizeof(uint16_t));
1067  memcpy(&gpio_output_configuration_packet->pashr_rate.r, &an_packet->data[14], sizeof(uint16_t));
1068  memcpy(&gpio_output_configuration_packet->tss1_rate.r, &an_packet->data[16], sizeof(uint16_t));
1069  memcpy(&gpio_output_configuration_packet->simrad_rate.r, &an_packet->data[18], sizeof(uint16_t));
1070  return 0;
1071  }
1072  else return 1;
1073 }
1074 
1076 {
1078  if(an_packet != NULL)
1079  {
1080  an_packet->data[0] = gpio_output_configuration_packet->permanent;
1081  an_packet->data[1] = gpio_output_configuration_packet->nmea_fix_behaviour;
1082  memcpy(&an_packet->data[2], &gpio_output_configuration_packet->gpzda_rate.r, sizeof(uint16_t));
1083  memcpy(&an_packet->data[4], &gpio_output_configuration_packet->gpgga_rate.r, sizeof(uint16_t));
1084  memcpy(&an_packet->data[6], &gpio_output_configuration_packet->gpvtg_rate.r, sizeof(uint16_t));
1085  memcpy(&an_packet->data[8], &gpio_output_configuration_packet->gprmc_rate.r, sizeof(uint16_t));
1086  memcpy(&an_packet->data[10], &gpio_output_configuration_packet->gphdt_rate.r, sizeof(uint16_t));
1087  memcpy(&an_packet->data[12], &gpio_output_configuration_packet->gpgll_rate.r, sizeof(uint16_t));
1088  memcpy(&an_packet->data[14], &gpio_output_configuration_packet->pashr_rate.r, sizeof(uint16_t));
1089  memcpy(&an_packet->data[16], &gpio_output_configuration_packet->tss1_rate.r, sizeof(uint16_t));
1090  memcpy(&an_packet->data[18], &gpio_output_configuration_packet->simrad_rate.r, sizeof(uint16_t));
1091  memset(&an_packet->data[20], 0, 13*sizeof(uint8_t));
1092  }
1093  return an_packet;
1094 }
an_packet_t * encode_external_odometer_packet(odometer_packet_t *external_odometer_packet)
an_packet_t * encode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet)
int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet)
an_packet_t * encode_external_heading_packet(external_heading_packet_t *external_heading_packet)
int decode_euler_orientation_standard_deviation_packet(euler_orientation_standard_deviation_packet_t *euler_orientation_standard_deviation, an_packet_t *an_packet)
int decode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet)
an_packet_t * encode_filter_options_packet(filter_options_packet_t *filter_options_packet)
int decode_position_standard_deviation_packet(position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet)
int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet)
union system_state_packet_t::@1 filter_status
union external_air_data_packet_t::@14 flags
uint8_t data[1]
an_packet_t * encode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet)
an_packet_t * encode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet)
int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet)
packet_period_t packet_periods[MAXIMUM_PACKET_PERIODS]
union satellite_t::@10 frequencies
int decode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet, an_packet_t *an_packet)
int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet)
int decode_acceleration_packet(acceleration_packet_t *acceleration, an_packet_t *an_packet)
int decode_angular_acceleration_packet(angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet)
int decode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet, an_packet_t *an_packet)
int decode_dcm_orientation_packet(dcm_orientation_packet_t *dcm_orientation_packet, an_packet_t *an_packet)
int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet)
int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet)
int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet)
int decode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet, an_packet_t *an_packet)
int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet)
an_packet_t * encode_zero_alignment_packet(zero_alignment_packet_t *zero_alignment_packet)
int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet)
an_packet_t * encode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet)
int decode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet, an_packet_t *an_packet)
an_packet_t * encode_external_time_packet(external_time_packet_t *external_time_packet)
int decode_external_position_packet(external_position_packet_t *external_position_packet, an_packet_t *an_packet)
int decode_odometer_packet(odometer_packet_t *external_odometer_packet, an_packet_t *an_packet)
an_packet_t * an_packet_allocate(uint8_t length, uint8_t id)
int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet)
int decode_quaternion_orientation_standard_deviation_packet(quaternion_orientation_standard_deviation_packet_t *quaternion_orientation_standard_deviation_packet, an_packet_t *an_packet)
union odometer_packet_t::@12 flags
float heading_standard_deviation
uint32_t unix_time_seconds
int decode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet, an_packet_t *an_packet)
int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet)
int decode_body_acceleration_packet(body_acceleration_packet_t *body_acceleration, an_packet_t *an_packet)
#define MAXIMUM_PACKET_PERIODS
int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet)
#define MAXIMUM_DETAILED_SATELLITES
an_packet_t * encode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet)
an_packet_t * encode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet)
uint8_t satellite_system
int decode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet, an_packet_t *an_packet)
an_packet_t * encode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet)
an_packet_t * encode_external_depth_packet(external_depth_packet_t *external_depth_packet)
int decode_magnetic_calibration_status_packet(magnetic_calibration_status_packet_t *magnetic_calibration_status_packet, an_packet_t *an_packet)
int decode_euler_orientation_packet(euler_orientation_packet_t *euler_orientation_packet, an_packet_t *an_packet)
satellite_t satellites[MAXIMUM_DETAILED_SATELLITES]
float wind_velocity[2]
float wind_standard_deviation
an_packet_t * encode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet)
float position_standard_deviation[3]
an_packet_t * encode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet)
int decode_external_heading_packet(external_heading_packet_t *external_heading_packet, an_packet_t *an_packet)
an_packet_t * encode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet)
int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet)
an_packet_t * encode_request_packet(uint8_t requested_packet_id)
int decode_geodetic_position_packet(geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet)
uint16_t azimuth
int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet)
int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet)
int decode_quaternion_orientation_packet(quaternion_orientation_packet_t *quaternion_orientation_packet, an_packet_t *an_packet)
int decode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet, an_packet_t *an_packet)
int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet)
an_packet_t * encode_external_position_packet(external_position_packet_t *external_position_packet)
int decode_angular_velocity_packet(angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet)
an_packet_t * encode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet)
int decode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet)
an_packet_t * encode_magnetic_calibration_configuration_packet(magnetic_calibration_configuration_packet_t *magnetic_calibration_configuration_packet)
union raw_gnss_packet_t::@8 flags
an_packet_t * encode_reset_packet()
uint8_t elevation
int decode_velocity_standard_deviation_packet(velocity_standard_deviation_packet_t *velocity_standard_deviation_packet, an_packet_t *an_packet)
int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet)
int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet)
union status_packet_t::@4 system_status
int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet)
int decode_local_magnetics_packet(local_magnetics_packet_t *local_magnetics_packet, an_packet_t *an_packet)
int decode_file_transfer_acknowledge_packet(file_transfer_acknowledge_packet_t *file_transfer_acknowledge_packet, an_packet_t *an_packet)
int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet)
union status_packet_t::@5 filter_status
an_packet_t * encode_restore_factory_settings_packet()
int decode_detailed_satellites_packet(detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet)
an_packet_t * encode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet)
an_packet_t * encode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet)
an_packet_t * encode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet)
int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet)
an_packet_t * encode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet)
int decode_wind_packet(wind_packet_t *wind_packet, an_packet_t *an_packet)
union system_state_packet_t::@0 system_status
int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet)
int decode_device_information_packet(device_information_packet_t *device_information_packet, an_packet_t *an_packet)
int decode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet, an_packet_t *an_packet)
int decode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet, an_packet_t *an_packet)
int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet)
an_packet_t * encode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet)
an_packet_t * encode_wind_packet(wind_packet_t *wind_packet)
int decode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet, an_packet_t *an_packet)


advanced_navigation_driver
Author(s):
autogenerated on Thu Jun 6 2019 19:13:08