00001
00002
00003
00005 #pragma pack(push)
00006 #pragma pack(1)
00007
00010
00011
00013 struct msg_acknowledge {
00014 uint8_t msgID;
00015 uint8_t sum1;
00016 uint8_t sum2;
00017 };
00018
00020 inline void
00021 send_msg_acknowledge(
00022 const uint8_t msgID,
00023 const uint8_t sum1,
00024 const uint8_t sum2)
00025 {
00026 _startMessage(MSG_ACKNOWLEDGE,
00027 sizeof(msgID) +
00028 sizeof(sum1) +
00029 sizeof(sum2) + 0);
00030 _emit(msgID);
00031 _emit(sum1);
00032 _emit(sum2);
00033 _endMessage();
00034 };
00035
00037 inline void
00038 unpack_msg_acknowledge(
00039 uint8_t &msgID,
00040 uint8_t &sum1,
00041 uint8_t &sum2)
00042 {
00043 uint8_t *__p = &_decodeBuf.payload[0];
00044 _unpack(__p, msgID);
00045 _unpack(__p, sum1);
00046 _unpack(__p, sum2);
00047 };
00049
00052
00053
00055 struct msg_status_text {
00056 uint8_t severity;
00057 char text[50];
00058 };
00059
00061 inline void
00062 send_msg_status_text(
00063 const uint8_t severity,
00064 const char (&text)[50])
00065 {
00066 _startMessage(MSG_STATUS_TEXT,
00067 sizeof(severity) +
00068 (sizeof(text[0]) * 50) + 0);
00069 _emit(severity);
00070 _emit(text, 50);
00071 _endMessage();
00072 };
00073
00075 inline void
00076 unpack_msg_status_text(
00077 uint8_t &severity,
00078 char (&text)[50])
00079 {
00080 uint8_t *__p = &_decodeBuf.payload[0];
00081 _unpack(__p, severity);
00082 _unpack(__p, text, 50);
00083 };
00085
00088
00089
00091 struct msg_heartbeat {
00092 uint8_t flightMode;
00093 uint16_t timeStamp;
00094 uint16_t batteryVoltage;
00095 uint16_t commandIndex;
00096 };
00097
00099 inline void
00100 send_msg_heartbeat(
00101 const uint8_t flightMode,
00102 const uint16_t timeStamp,
00103 const uint16_t batteryVoltage,
00104 const uint16_t commandIndex)
00105 {
00106 _startMessage(MSG_HEARTBEAT,
00107 sizeof(flightMode) +
00108 sizeof(timeStamp) +
00109 sizeof(batteryVoltage) +
00110 sizeof(commandIndex) + 0);
00111 _emit(flightMode);
00112 _emit(timeStamp);
00113 _emit(batteryVoltage);
00114 _emit(commandIndex);
00115 _endMessage();
00116 };
00117
00119 inline void
00120 unpack_msg_heartbeat(
00121 uint8_t &flightMode,
00122 uint16_t &timeStamp,
00123 uint16_t &batteryVoltage,
00124 uint16_t &commandIndex)
00125 {
00126 uint8_t *__p = &_decodeBuf.payload[0];
00127 _unpack(__p, flightMode);
00128 _unpack(__p, timeStamp);
00129 _unpack(__p, batteryVoltage);
00130 _unpack(__p, commandIndex);
00131 };
00133
00136
00137
00139 struct msg_attitude {
00140 int16_t roll;
00141 int16_t pitch;
00142 uint16_t yaw;
00143 };
00144
00146 inline void
00147 send_msg_attitude(
00148 const int16_t roll,
00149 const int16_t pitch,
00150 const uint16_t yaw)
00151 {
00152 _startMessage(MSG_ATTITUDE,
00153 sizeof(roll) +
00154 sizeof(pitch) +
00155 sizeof(yaw) + 0);
00156 _emit(roll);
00157 _emit(pitch);
00158 _emit(yaw);
00159 _endMessage();
00160 };
00161
00163 inline void
00164 unpack_msg_attitude(
00165 int16_t &roll,
00166 int16_t &pitch,
00167 uint16_t &yaw)
00168 {
00169 uint8_t *__p = &_decodeBuf.payload[0];
00170 _unpack(__p, roll);
00171 _unpack(__p, pitch);
00172 _unpack(__p, yaw);
00173 };
00175
00178
00179
00181 struct msg_location {
00182 int32_t latitude;
00183 int32_t longitude;
00184 int32_t altitude;
00185 uint16_t groundSpeed;
00186 uint16_t groundCourse;
00187 uint32_t timeOfWeek;
00188 };
00189
00191 inline void
00192 send_msg_location(
00193 const int32_t latitude,
00194 const int32_t longitude,
00195 const int32_t altitude,
00196 const uint16_t groundSpeed,
00197 const uint16_t groundCourse,
00198 const uint32_t timeOfWeek)
00199 {
00200 _startMessage(MSG_LOCATION,
00201 sizeof(latitude) +
00202 sizeof(longitude) +
00203 sizeof(altitude) +
00204 sizeof(groundSpeed) +
00205 sizeof(groundCourse) +
00206 sizeof(timeOfWeek) + 0);
00207 _emit(latitude);
00208 _emit(longitude);
00209 _emit(altitude);
00210 _emit(groundSpeed);
00211 _emit(groundCourse);
00212 _emit(timeOfWeek);
00213 _endMessage();
00214 };
00215
00217 inline void
00218 unpack_msg_location(
00219 int32_t &latitude,
00220 int32_t &longitude,
00221 int32_t &altitude,
00222 uint16_t &groundSpeed,
00223 uint16_t &groundCourse,
00224 uint32_t &timeOfWeek)
00225 {
00226 uint8_t *__p = &_decodeBuf.payload[0];
00227 _unpack(__p, latitude);
00228 _unpack(__p, longitude);
00229 _unpack(__p, altitude);
00230 _unpack(__p, groundSpeed);
00231 _unpack(__p, groundCourse);
00232 _unpack(__p, timeOfWeek);
00233 };
00235
00238
00239
00241 struct msg_pressure {
00242 int32_t pressureAltitude;
00243 int16_t airSpeed;
00244 };
00245
00247 inline void
00248 send_msg_pressure(
00249 const int32_t pressureAltitude,
00250 const int16_t airSpeed)
00251 {
00252 _startMessage(MSG_PRESSURE,
00253 sizeof(pressureAltitude) +
00254 sizeof(airSpeed) + 0);
00255 _emit(pressureAltitude);
00256 _emit(airSpeed);
00257 _endMessage();
00258 };
00259
00261 inline void
00262 unpack_msg_pressure(
00263 int32_t &pressureAltitude,
00264 int16_t &airSpeed)
00265 {
00266 uint8_t *__p = &_decodeBuf.payload[0];
00267 _unpack(__p, pressureAltitude);
00268 _unpack(__p, airSpeed);
00269 };
00271
00274
00275
00277 struct msg_perf_report {
00278 uint32_t interval;
00279 uint16_t mainLoopCycles;
00280 uint8_t mainLoopCycleTime;
00281 uint8_t gyroSaturationCount;
00282 uint8_t adcConstraintCount;
00283 uint8_t renormSqrtCount;
00284 uint8_t renormBlowupCount;
00285 uint8_t gpsFixCount;
00286 uint16_t imuHealth;
00287 uint16_t gcsMessageCount;
00288 };
00289
00291 inline void
00292 send_msg_perf_report(
00293 const uint32_t interval,
00294 const uint16_t mainLoopCycles,
00295 const uint8_t mainLoopCycleTime,
00296 const uint8_t gyroSaturationCount,
00297 const uint8_t adcConstraintCount,
00298 const uint8_t renormSqrtCount,
00299 const uint8_t renormBlowupCount,
00300 const uint8_t gpsFixCount,
00301 const uint16_t imuHealth,
00302 const uint16_t gcsMessageCount)
00303 {
00304 _startMessage(MSG_PERF_REPORT,
00305 sizeof(interval) +
00306 sizeof(mainLoopCycles) +
00307 sizeof(mainLoopCycleTime) +
00308 sizeof(gyroSaturationCount) +
00309 sizeof(adcConstraintCount) +
00310 sizeof(renormSqrtCount) +
00311 sizeof(renormBlowupCount) +
00312 sizeof(gpsFixCount) +
00313 sizeof(imuHealth) +
00314 sizeof(gcsMessageCount) + 0);
00315 _emit(interval);
00316 _emit(mainLoopCycles);
00317 _emit(mainLoopCycleTime);
00318 _emit(gyroSaturationCount);
00319 _emit(adcConstraintCount);
00320 _emit(renormSqrtCount);
00321 _emit(renormBlowupCount);
00322 _emit(gpsFixCount);
00323 _emit(imuHealth);
00324 _emit(gcsMessageCount);
00325 _endMessage();
00326 };
00327
00329 inline void
00330 unpack_msg_perf_report(
00331 uint32_t &interval,
00332 uint16_t &mainLoopCycles,
00333 uint8_t &mainLoopCycleTime,
00334 uint8_t &gyroSaturationCount,
00335 uint8_t &adcConstraintCount,
00336 uint8_t &renormSqrtCount,
00337 uint8_t &renormBlowupCount,
00338 uint8_t &gpsFixCount,
00339 uint16_t &imuHealth,
00340 uint16_t &gcsMessageCount)
00341 {
00342 uint8_t *__p = &_decodeBuf.payload[0];
00343 _unpack(__p, interval);
00344 _unpack(__p, mainLoopCycles);
00345 _unpack(__p, mainLoopCycleTime);
00346 _unpack(__p, gyroSaturationCount);
00347 _unpack(__p, adcConstraintCount);
00348 _unpack(__p, renormSqrtCount);
00349 _unpack(__p, renormBlowupCount);
00350 _unpack(__p, gpsFixCount);
00351 _unpack(__p, imuHealth);
00352 _unpack(__p, gcsMessageCount);
00353 };
00355
00358
00359
00361 struct msg_version_request {
00362 uint8_t systemType;
00363 uint8_t systemID;
00364 };
00365
00367 inline void
00368 send_msg_version_request(
00369 const uint8_t systemType,
00370 const uint8_t systemID)
00371 {
00372 _startMessage(MSG_VERSION_REQUEST,
00373 sizeof(systemType) +
00374 sizeof(systemID) + 0);
00375 _emit(systemType);
00376 _emit(systemID);
00377 _endMessage();
00378 };
00379
00381 inline void
00382 unpack_msg_version_request(
00383 uint8_t &systemType,
00384 uint8_t &systemID)
00385 {
00386 uint8_t *__p = &_decodeBuf.payload[0];
00387 _unpack(__p, systemType);
00388 _unpack(__p, systemID);
00389 };
00391
00394
00395
00397 struct msg_version {
00398 uint8_t systemType;
00399 uint8_t systemID;
00400 uint8_t firmwareVersion[3];
00401 };
00402
00404 inline void
00405 send_msg_version(
00406 const uint8_t systemType,
00407 const uint8_t systemID,
00408 const uint8_t (&firmwareVersion)[3])
00409 {
00410 _startMessage(MSG_VERSION,
00411 sizeof(systemType) +
00412 sizeof(systemID) +
00413 (sizeof(firmwareVersion[0]) * 3) + 0);
00414 _emit(systemType);
00415 _emit(systemID);
00416 _emit(firmwareVersion, 3);
00417 _endMessage();
00418 };
00419
00421 inline void
00422 unpack_msg_version(
00423 uint8_t &systemType,
00424 uint8_t &systemID,
00425 uint8_t (&firmwareVersion)[3])
00426 {
00427 uint8_t *__p = &_decodeBuf.payload[0];
00428 _unpack(__p, systemType);
00429 _unpack(__p, systemID);
00430 _unpack(__p, firmwareVersion, 3);
00431 };
00433
00436
00437
00439 struct msg_command_request {
00440 uint16_t UNSPECIFIED;
00441 };
00442
00444 inline void
00445 send_msg_command_request(
00446 const uint16_t UNSPECIFIED)
00447 {
00448 _startMessage(MSG_COMMAND_REQUEST,
00449 sizeof(UNSPECIFIED) + 0);
00450 _emit(UNSPECIFIED);
00451 _endMessage();
00452 };
00453
00455 inline void
00456 unpack_msg_command_request(
00457 uint16_t &UNSPECIFIED)
00458 {
00459 uint8_t *__p = &_decodeBuf.payload[0];
00460 _unpack(__p, UNSPECIFIED);
00461 };
00463
00466
00467
00469 struct msg_command_upload {
00470 uint8_t action;
00471 uint16_t itemNumber;
00472 uint16_t listLength;
00473 uint8_t commandID;
00474 uint8_t p1;
00475 int32_t p2;
00476 int32_t p3;
00477 int32_t p4;
00478 };
00479
00481 inline void
00482 send_msg_command_upload(
00483 const uint8_t action,
00484 const uint16_t itemNumber,
00485 const uint16_t listLength,
00486 const uint8_t commandID,
00487 const uint8_t p1,
00488 const int32_t p2,
00489 const int32_t p3,
00490 const int32_t p4)
00491 {
00492 _startMessage(MSG_COMMAND_UPLOAD,
00493 sizeof(action) +
00494 sizeof(itemNumber) +
00495 sizeof(listLength) +
00496 sizeof(commandID) +
00497 sizeof(p1) +
00498 sizeof(p2) +
00499 sizeof(p3) +
00500 sizeof(p4) + 0);
00501 _emit(action);
00502 _emit(itemNumber);
00503 _emit(listLength);
00504 _emit(commandID);
00505 _emit(p1);
00506 _emit(p2);
00507 _emit(p3);
00508 _emit(p4);
00509 _endMessage();
00510 };
00511
00513 inline void
00514 unpack_msg_command_upload(
00515 uint8_t &action,
00516 uint16_t &itemNumber,
00517 uint16_t &listLength,
00518 uint8_t &commandID,
00519 uint8_t &p1,
00520 int32_t &p2,
00521 int32_t &p3,
00522 int32_t &p4)
00523 {
00524 uint8_t *__p = &_decodeBuf.payload[0];
00525 _unpack(__p, action);
00526 _unpack(__p, itemNumber);
00527 _unpack(__p, listLength);
00528 _unpack(__p, commandID);
00529 _unpack(__p, p1);
00530 _unpack(__p, p2);
00531 _unpack(__p, p3);
00532 _unpack(__p, p4);
00533 };
00535
00538
00539
00541 struct msg_command_list {
00542 uint16_t itemNumber;
00543 uint16_t listLength;
00544 uint8_t commandID;
00545 uint8_t p1;
00546 int32_t p2;
00547 int32_t p3;
00548 int32_t p4;
00549 };
00550
00552 inline void
00553 send_msg_command_list(
00554 const uint16_t itemNumber,
00555 const uint16_t listLength,
00556 const uint8_t commandID,
00557 const uint8_t p1,
00558 const int32_t p2,
00559 const int32_t p3,
00560 const int32_t p4)
00561 {
00562 _startMessage(MSG_COMMAND_LIST,
00563 sizeof(itemNumber) +
00564 sizeof(listLength) +
00565 sizeof(commandID) +
00566 sizeof(p1) +
00567 sizeof(p2) +
00568 sizeof(p3) +
00569 sizeof(p4) + 0);
00570 _emit(itemNumber);
00571 _emit(listLength);
00572 _emit(commandID);
00573 _emit(p1);
00574 _emit(p2);
00575 _emit(p3);
00576 _emit(p4);
00577 _endMessage();
00578 };
00579
00581 inline void
00582 unpack_msg_command_list(
00583 uint16_t &itemNumber,
00584 uint16_t &listLength,
00585 uint8_t &commandID,
00586 uint8_t &p1,
00587 int32_t &p2,
00588 int32_t &p3,
00589 int32_t &p4)
00590 {
00591 uint8_t *__p = &_decodeBuf.payload[0];
00592 _unpack(__p, itemNumber);
00593 _unpack(__p, listLength);
00594 _unpack(__p, commandID);
00595 _unpack(__p, p1);
00596 _unpack(__p, p2);
00597 _unpack(__p, p3);
00598 _unpack(__p, p4);
00599 };
00601
00604
00605
00607 struct msg_command_mode_change {
00608 uint16_t UNSPECIFIED;
00609 };
00610
00612 inline void
00613 send_msg_command_mode_change(
00614 const uint16_t UNSPECIFIED)
00615 {
00616 _startMessage(MSG_COMMAND_MODE_CHANGE,
00617 sizeof(UNSPECIFIED) + 0);
00618 _emit(UNSPECIFIED);
00619 _endMessage();
00620 };
00621
00623 inline void
00624 unpack_msg_command_mode_change(
00625 uint16_t &UNSPECIFIED)
00626 {
00627 uint8_t *__p = &_decodeBuf.payload[0];
00628 _unpack(__p, UNSPECIFIED);
00629 };
00631
00634
00635
00637 struct msg_value_request {
00638 uint8_t valueID;
00639 uint8_t broadcast;
00640 };
00641
00643 inline void
00644 send_msg_value_request(
00645 const uint8_t valueID,
00646 const uint8_t broadcast)
00647 {
00648 _startMessage(MSG_VALUE_REQUEST,
00649 sizeof(valueID) +
00650 sizeof(broadcast) + 0);
00651 _emit(valueID);
00652 _emit(broadcast);
00653 _endMessage();
00654 };
00655
00657 inline void
00658 unpack_msg_value_request(
00659 uint8_t &valueID,
00660 uint8_t &broadcast)
00661 {
00662 uint8_t *__p = &_decodeBuf.payload[0];
00663 _unpack(__p, valueID);
00664 _unpack(__p, broadcast);
00665 };
00667
00670
00671
00673 struct msg_value_set {
00674 uint8_t valueID;
00675 uint32_t value;
00676 };
00677
00679 inline void
00680 send_msg_value_set(
00681 const uint8_t valueID,
00682 const uint32_t value)
00683 {
00684 _startMessage(MSG_VALUE_SET,
00685 sizeof(valueID) +
00686 sizeof(value) + 0);
00687 _emit(valueID);
00688 _emit(value);
00689 _endMessage();
00690 };
00691
00693 inline void
00694 unpack_msg_value_set(
00695 uint8_t &valueID,
00696 uint32_t &value)
00697 {
00698 uint8_t *__p = &_decodeBuf.payload[0];
00699 _unpack(__p, valueID);
00700 _unpack(__p, value);
00701 };
00703
00706
00707
00709 struct msg_value {
00710 uint8_t valueID;
00711 uint32_t value;
00712 };
00713
00715 inline void
00716 send_msg_value(
00717 const uint8_t valueID,
00718 const uint32_t value)
00719 {
00720 _startMessage(MSG_VALUE,
00721 sizeof(valueID) +
00722 sizeof(value) + 0);
00723 _emit(valueID);
00724 _emit(value);
00725 _endMessage();
00726 };
00727
00729 inline void
00730 unpack_msg_value(
00731 uint8_t &valueID,
00732 uint32_t &value)
00733 {
00734 uint8_t *__p = &_decodeBuf.payload[0];
00735 _unpack(__p, valueID);
00736 _unpack(__p, value);
00737 };
00739
00742
00743
00745 struct msg_pid_request {
00746 uint8_t pidSet;
00747 };
00748
00750 inline void
00751 send_msg_pid_request(
00752 const uint8_t pidSet)
00753 {
00754 _startMessage(MSG_PID_REQUEST,
00755 sizeof(pidSet) + 0);
00756 _emit(pidSet);
00757 _endMessage();
00758 };
00759
00761 inline void
00762 unpack_msg_pid_request(
00763 uint8_t &pidSet)
00764 {
00765 uint8_t *__p = &_decodeBuf.payload[0];
00766 _unpack(__p, pidSet);
00767 };
00769
00772
00773
00775 struct msg_pid_set {
00776 uint8_t pidSet;
00777 int32_t p;
00778 int32_t i;
00779 int32_t d;
00780 int16_t integratorMax;
00781 };
00782
00784 inline void
00785 send_msg_pid_set(
00786 const uint8_t pidSet,
00787 const int32_t p,
00788 const int32_t i,
00789 const int32_t d,
00790 const int16_t integratorMax)
00791 {
00792 _startMessage(MSG_PID_SET,
00793 sizeof(pidSet) +
00794 sizeof(p) +
00795 sizeof(i) +
00796 sizeof(d) +
00797 sizeof(integratorMax) + 0);
00798 _emit(pidSet);
00799 _emit(p);
00800 _emit(i);
00801 _emit(d);
00802 _emit(integratorMax);
00803 _endMessage();
00804 };
00805
00807 inline void
00808 unpack_msg_pid_set(
00809 uint8_t &pidSet,
00810 int32_t &p,
00811 int32_t &i,
00812 int32_t &d,
00813 int16_t &integratorMax)
00814 {
00815 uint8_t *__p = &_decodeBuf.payload[0];
00816 _unpack(__p, pidSet);
00817 _unpack(__p, p);
00818 _unpack(__p, i);
00819 _unpack(__p, d);
00820 _unpack(__p, integratorMax);
00821 };
00823
00826
00827
00829 struct msg_pid {
00830 uint8_t pidSet;
00831 int32_t p;
00832 int32_t i;
00833 int32_t d;
00834 int16_t integratorMax;
00835 };
00836
00838 inline void
00839 send_msg_pid(
00840 const uint8_t pidSet,
00841 const int32_t p,
00842 const int32_t i,
00843 const int32_t d,
00844 const int16_t integratorMax)
00845 {
00846 _startMessage(MSG_PID,
00847 sizeof(pidSet) +
00848 sizeof(p) +
00849 sizeof(i) +
00850 sizeof(d) +
00851 sizeof(integratorMax) + 0);
00852 _emit(pidSet);
00853 _emit(p);
00854 _emit(i);
00855 _emit(d);
00856 _emit(integratorMax);
00857 _endMessage();
00858 };
00859
00861 inline void
00862 unpack_msg_pid(
00863 uint8_t &pidSet,
00864 int32_t &p,
00865 int32_t &i,
00866 int32_t &d,
00867 int16_t &integratorMax)
00868 {
00869 uint8_t *__p = &_decodeBuf.payload[0];
00870 _unpack(__p, pidSet);
00871 _unpack(__p, p);
00872 _unpack(__p, i);
00873 _unpack(__p, d);
00874 _unpack(__p, integratorMax);
00875 };
00877
00880
00881
00883 struct msg_trim_startup {
00884 uint16_t value[8];
00885 };
00886
00888 inline void
00889 send_msg_trim_startup(
00890 const uint16_t (&value)[8])
00891 {
00892 _startMessage(MSG_TRIM_STARTUP,
00893 (sizeof(value[0]) * 8) + 0);
00894 _emit(value, 8);
00895 _endMessage();
00896 };
00897
00899 inline void
00900 unpack_msg_trim_startup(
00901 uint16_t (&value)[8])
00902 {
00903 uint8_t *__p = &_decodeBuf.payload[0];
00904 _unpack(__p, value, 8);
00905 };
00907
00910
00911
00913 struct msg_trim_min {
00914 uint16_t value[8];
00915 };
00916
00918 inline void
00919 send_msg_trim_min(
00920 const uint16_t (&value)[8])
00921 {
00922 _startMessage(MSG_TRIM_MIN,
00923 (sizeof(value[0]) * 8) + 0);
00924 _emit(value, 8);
00925 _endMessage();
00926 };
00927
00929 inline void
00930 unpack_msg_trim_min(
00931 uint16_t (&value)[8])
00932 {
00933 uint8_t *__p = &_decodeBuf.payload[0];
00934 _unpack(__p, value, 8);
00935 };
00937
00940
00941
00943 struct msg_trim_max {
00944 uint16_t value[8];
00945 };
00946
00948 inline void
00949 send_msg_trim_max(
00950 const uint16_t (&value)[8])
00951 {
00952 _startMessage(MSG_TRIM_MAX,
00953 (sizeof(value[0]) * 8) + 0);
00954 _emit(value, 8);
00955 _endMessage();
00956 };
00957
00959 inline void
00960 unpack_msg_trim_max(
00961 uint16_t (&value)[8])
00962 {
00963 uint8_t *__p = &_decodeBuf.payload[0];
00964 _unpack(__p, value, 8);
00965 };
00967
00970
00971
00973 struct msg_radio_out {
00974 uint16_t value[8];
00975 };
00976
00978 inline void
00979 send_msg_radio_out(
00980 const uint16_t (&value)[8])
00981 {
00982 _startMessage(MSG_RADIO_OUT,
00983 (sizeof(value[0]) * 8) + 0);
00984 _emit(value, 8);
00985 _endMessage();
00986 };
00987
00989 inline void
00990 unpack_msg_radio_out(
00991 uint16_t (&value)[8])
00992 {
00993 uint8_t *__p = &_decodeBuf.payload[0];
00994 _unpack(__p, value, 8);
00995 };
00997
01000
01001
01003 struct msg_sensor {
01004 uint16_t UNSPECIFIED;
01005 };
01006
01008 inline void
01009 send_msg_sensor(
01010 const uint16_t UNSPECIFIED)
01011 {
01012 _startMessage(MSG_SENSOR,
01013 sizeof(UNSPECIFIED) + 0);
01014 _emit(UNSPECIFIED);
01015 _endMessage();
01016 };
01017
01019 inline void
01020 unpack_msg_sensor(
01021 uint16_t &UNSPECIFIED)
01022 {
01023 uint8_t *__p = &_decodeBuf.payload[0];
01024 _unpack(__p, UNSPECIFIED);
01025 };
01027
01030
01031
01033 struct msg_servo_out {
01034 int16_t value[8];
01035 };
01036
01038 inline void
01039 send_msg_servo_out(
01040 const int16_t (&value)[8])
01041 {
01042 _startMessage(MSG_SERVO_OUT,
01043 (sizeof(value[0]) * 8) + 0);
01044 _emit(value, 8);
01045 _endMessage();
01046 };
01047
01049 inline void
01050 unpack_msg_servo_out(
01051 int16_t (&value)[8])
01052 {
01053 uint8_t *__p = &_decodeBuf.payload[0];
01054 _unpack(__p, value, 8);
01055 };
01057
01060
01061
01063 struct msg_pin_request {
01064 uint16_t UNSPECIFIED;
01065 };
01066
01068 inline void
01069 send_msg_pin_request(
01070 const uint16_t UNSPECIFIED)
01071 {
01072 _startMessage(MSG_PIN_REQUEST,
01073 sizeof(UNSPECIFIED) + 0);
01074 _emit(UNSPECIFIED);
01075 _endMessage();
01076 };
01077
01079 inline void
01080 unpack_msg_pin_request(
01081 uint16_t &UNSPECIFIED)
01082 {
01083 uint8_t *__p = &_decodeBuf.payload[0];
01084 _unpack(__p, UNSPECIFIED);
01085 };
01087
01090
01091
01093 struct msg_pin_set {
01094 uint16_t UNSPECIFIED;
01095 };
01096
01098 inline void
01099 send_msg_pin_set(
01100 const uint16_t UNSPECIFIED)
01101 {
01102 _startMessage(MSG_PIN_SET,
01103 sizeof(UNSPECIFIED) + 0);
01104 _emit(UNSPECIFIED);
01105 _endMessage();
01106 };
01107
01109 inline void
01110 unpack_msg_pin_set(
01111 uint16_t &UNSPECIFIED)
01112 {
01113 uint8_t *__p = &_decodeBuf.payload[0];
01114 _unpack(__p, UNSPECIFIED);
01115 };
01117
01120
01121
01123 struct msg_dataflash_request {
01124 uint16_t UNSPECIFIED;
01125 };
01126
01128 inline void
01129 send_msg_dataflash_request(
01130 const uint16_t UNSPECIFIED)
01131 {
01132 _startMessage(MSG_DATAFLASH_REQUEST,
01133 sizeof(UNSPECIFIED) + 0);
01134 _emit(UNSPECIFIED);
01135 _endMessage();
01136 };
01137
01139 inline void
01140 unpack_msg_dataflash_request(
01141 uint16_t &UNSPECIFIED)
01142 {
01143 uint8_t *__p = &_decodeBuf.payload[0];
01144 _unpack(__p, UNSPECIFIED);
01145 };
01147
01150
01151
01153 struct msg_dataflash_set {
01154 uint16_t UNSPECIFIED;
01155 };
01156
01158 inline void
01159 send_msg_dataflash_set(
01160 const uint16_t UNSPECIFIED)
01161 {
01162 _startMessage(MSG_DATAFLASH_SET,
01163 sizeof(UNSPECIFIED) + 0);
01164 _emit(UNSPECIFIED);
01165 _endMessage();
01166 };
01167
01169 inline void
01170 unpack_msg_dataflash_set(
01171 uint16_t &UNSPECIFIED)
01172 {
01173 uint8_t *__p = &_decodeBuf.payload[0];
01174 _unpack(__p, UNSPECIFIED);
01175 };
01177
01180
01181
01183 struct msg_eeprom_request {
01184 uint16_t UNSPECIFIED;
01185 };
01186
01188 inline void
01189 send_msg_eeprom_request(
01190 const uint16_t UNSPECIFIED)
01191 {
01192 _startMessage(MSG_EEPROM_REQUEST,
01193 sizeof(UNSPECIFIED) + 0);
01194 _emit(UNSPECIFIED);
01195 _endMessage();
01196 };
01197
01199 inline void
01200 unpack_msg_eeprom_request(
01201 uint16_t &UNSPECIFIED)
01202 {
01203 uint8_t *__p = &_decodeBuf.payload[0];
01204 _unpack(__p, UNSPECIFIED);
01205 };
01207
01210
01211
01213 struct msg_eeprom_set {
01214 uint16_t UNSPECIFIED;
01215 };
01216
01218 inline void
01219 send_msg_eeprom_set(
01220 const uint16_t UNSPECIFIED)
01221 {
01222 _startMessage(MSG_EEPROM_SET,
01223 sizeof(UNSPECIFIED) + 0);
01224 _emit(UNSPECIFIED);
01225 _endMessage();
01226 };
01227
01229 inline void
01230 unpack_msg_eeprom_set(
01231 uint16_t &UNSPECIFIED)
01232 {
01233 uint8_t *__p = &_decodeBuf.payload[0];
01234 _unpack(__p, UNSPECIFIED);
01235 };
01237
01240
01241
01243 struct msg_position_correct {
01244 int16_t latError;
01245 int16_t lonError;
01246 int16_t altError;
01247 int16_t groundSpeedError;
01248 };
01249
01251 inline void
01252 send_msg_position_correct(
01253 const int16_t latError,
01254 const int16_t lonError,
01255 const int16_t altError,
01256 const int16_t groundSpeedError)
01257 {
01258 _startMessage(MSG_POSITION_CORRECT,
01259 sizeof(latError) +
01260 sizeof(lonError) +
01261 sizeof(altError) +
01262 sizeof(groundSpeedError) + 0);
01263 _emit(latError);
01264 _emit(lonError);
01265 _emit(altError);
01266 _emit(groundSpeedError);
01267 _endMessage();
01268 };
01269
01271 inline void
01272 unpack_msg_position_correct(
01273 int16_t &latError,
01274 int16_t &lonError,
01275 int16_t &altError,
01276 int16_t &groundSpeedError)
01277 {
01278 uint8_t *__p = &_decodeBuf.payload[0];
01279 _unpack(__p, latError);
01280 _unpack(__p, lonError);
01281 _unpack(__p, altError);
01282 _unpack(__p, groundSpeedError);
01283 };
01285
01288
01289
01291 struct msg_attitude_correct {
01292 int16_t rollError;
01293 int16_t pitchError;
01294 int16_t yawError;
01295 };
01296
01298 inline void
01299 send_msg_attitude_correct(
01300 const int16_t rollError,
01301 const int16_t pitchError,
01302 const int16_t yawError)
01303 {
01304 _startMessage(MSG_ATTITUDE_CORRECT,
01305 sizeof(rollError) +
01306 sizeof(pitchError) +
01307 sizeof(yawError) + 0);
01308 _emit(rollError);
01309 _emit(pitchError);
01310 _emit(yawError);
01311 _endMessage();
01312 };
01313
01315 inline void
01316 unpack_msg_attitude_correct(
01317 int16_t &rollError,
01318 int16_t &pitchError,
01319 int16_t &yawError)
01320 {
01321 uint8_t *__p = &_decodeBuf.payload[0];
01322 _unpack(__p, rollError);
01323 _unpack(__p, pitchError);
01324 _unpack(__p, yawError);
01325 };
01327
01330
01331
01333 struct msg_position_set {
01334 int32_t latitude;
01335 int32_t longitude;
01336 int32_t altitude;
01337 uint16_t heading;
01338 };
01339
01341 inline void
01342 send_msg_position_set(
01343 const int32_t latitude,
01344 const int32_t longitude,
01345 const int32_t altitude,
01346 const uint16_t heading)
01347 {
01348 _startMessage(MSG_POSITION_SET,
01349 sizeof(latitude) +
01350 sizeof(longitude) +
01351 sizeof(altitude) +
01352 sizeof(heading) + 0);
01353 _emit(latitude);
01354 _emit(longitude);
01355 _emit(altitude);
01356 _emit(heading);
01357 _endMessage();
01358 };
01359
01361 inline void
01362 unpack_msg_position_set(
01363 int32_t &latitude,
01364 int32_t &longitude,
01365 int32_t &altitude,
01366 uint16_t &heading)
01367 {
01368 uint8_t *__p = &_decodeBuf.payload[0];
01369 _unpack(__p, latitude);
01370 _unpack(__p, longitude);
01371 _unpack(__p, altitude);
01372 _unpack(__p, heading);
01373 };
01375
01378
01379
01381 struct msg_attitude_set {
01382 int16_t roll;
01383 int16_t pitch;
01384 uint16_t yaw;
01385 };
01386
01388 inline void
01389 send_msg_attitude_set(
01390 const int16_t roll,
01391 const int16_t pitch,
01392 const uint16_t yaw)
01393 {
01394 _startMessage(MSG_ATTITUDE_SET,
01395 sizeof(roll) +
01396 sizeof(pitch) +
01397 sizeof(yaw) + 0);
01398 _emit(roll);
01399 _emit(pitch);
01400 _emit(yaw);
01401 _endMessage();
01402 };
01403
01405 inline void
01406 unpack_msg_attitude_set(
01407 int16_t &roll,
01408 int16_t &pitch,
01409 uint16_t &yaw)
01410 {
01411 uint8_t *__p = &_decodeBuf.payload[0];
01412 _unpack(__p, roll);
01413 _unpack(__p, pitch);
01414 _unpack(__p, yaw);
01415 };
01417
01420 enum MessageID {
01421 MSG_PID = 0x42,
01422 MSG_DATAFLASH_REQUEST = 0x90,
01423 MSG_DATAFLASH_SET = 0x91,
01424 MSG_SENSOR = 0x60,
01425 MSG_VALUE_REQUEST = 0x30,
01426 MSG_VALUE_SET = 0x31,
01427 MSG_VALUE = 0x32,
01428 MSG_PIN_REQUEST = 0x80,
01429 MSG_PIN_SET = 0x81,
01430 MSG_POSITION_CORRECT = 0xb0,
01431 MSG_ACKNOWLEDGE = 0x0,
01432 MSG_ATTITUDE_CORRECT = 0xb1,
01433 MSG_HEARTBEAT = 0x1,
01434 MSG_POSITION_SET = 0xb2,
01435 MSG_ATTITUDE = 0x2,
01436 MSG_ATTITUDE_SET = 0xb3,
01437 MSG_LOCATION = 0x3,
01438 MSG_PRESSURE = 0x4,
01439 MSG_TRIM_STARTUP = 0x50,
01440 MSG_STATUS_TEXT = 0x5,
01441 MSG_TRIM_MIN = 0x51,
01442 MSG_PERF_REPORT = 0x6,
01443 MSG_TRIM_MAX = 0x52,
01444 MSG_VERSION_REQUEST = 0x7,
01445 MSG_RADIO_OUT = 0x53,
01446 MSG_VERSION = 0x8,
01447 MSG_COMMAND_REQUEST = 0x20,
01448 MSG_COMMAND_UPLOAD = 0x21,
01449 MSG_COMMAND_LIST = 0x22,
01450 MSG_COMMAND_MODE_CHANGE = 0x23,
01451 MSG_SERVO_OUT = 0x70,
01452 MSG_EEPROM_REQUEST = 0xa0,
01453 MSG_EEPROM_SET = 0xa1,
01454 MSG_PID_REQUEST = 0x40,
01455 MSG_PID_SET = 0x41,
01456 MSG_ANY = 0xfe,
01457 MSG_NULL = 0xff
01458 };
01459
01462 union _binCommBufferSizer {
01463 struct msg_acknowledge msg_acknowledge;
01464 struct msg_status_text msg_status_text;
01465 struct msg_heartbeat msg_heartbeat;
01466 struct msg_attitude msg_attitude;
01467 struct msg_location msg_location;
01468 struct msg_pressure msg_pressure;
01469 struct msg_perf_report msg_perf_report;
01470 struct msg_version_request msg_version_request;
01471 struct msg_version msg_version;
01472 struct msg_command_request msg_command_request;
01473 struct msg_command_upload msg_command_upload;
01474 struct msg_command_list msg_command_list;
01475 struct msg_command_mode_change msg_command_mode_change;
01476 struct msg_value_request msg_value_request;
01477 struct msg_value_set msg_value_set;
01478 struct msg_value msg_value;
01479 struct msg_pid_request msg_pid_request;
01480 struct msg_pid_set msg_pid_set;
01481 struct msg_pid msg_pid;
01482 struct msg_trim_startup msg_trim_startup;
01483 struct msg_trim_min msg_trim_min;
01484 struct msg_trim_max msg_trim_max;
01485 struct msg_radio_out msg_radio_out;
01486 struct msg_sensor msg_sensor;
01487 struct msg_servo_out msg_servo_out;
01488 struct msg_pin_request msg_pin_request;
01489 struct msg_pin_set msg_pin_set;
01490 struct msg_dataflash_request msg_dataflash_request;
01491 struct msg_dataflash_set msg_dataflash_set;
01492 struct msg_eeprom_request msg_eeprom_request;
01493 struct msg_eeprom_set msg_eeprom_set;
01494 struct msg_position_correct msg_position_correct;
01495 struct msg_attitude_correct msg_attitude_correct;
01496 struct msg_position_set msg_position_set;
01497 struct msg_attitude_set msg_attitude_set;
01498 };
01499 #define BINCOMM_MAX_MESSAGE_SIZE sizeof(union _binCommBufferSizer)
01500
01501 #pragma pack(pop)