Projet Drone de surveillance du labo TRSE (INGESUP)

Dependencies:   mbed PID ADXL345 Camera_LS_Y201 ITG3200 RangeFinder mbos xbee_lib Motor Servo

Files at this revision

API Documentation at this revision

Comitter:
Gaetan
Date:
Wed Mar 19 11:01:10 2014 +0000
Parent:
35:95cb34636703
Commit message:
Checksum correct pour l'envoi de n'importe quel message Mavlink. Reste ? g?rer la reception de messages

Changed in this revision

Module_Communication/MAVlink/include/checksum.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/protocol.h Show annotated file Show diff for this revision Revisions of this file
--- a/Module_Communication/MAVlink/include/checksum.h	Wed Mar 19 09:27:19 2014 +0000
+++ b/Module_Communication/MAVlink/include/checksum.h	Wed Mar 19 11:01:10 2014 +0000
@@ -18,6 +18,14 @@
 #define X25_VALIDATE_CRC 0xf0b8
 
 /**
+ *
+ * Additionnal seed for crc calculation in MavLink 1.0 
+ *
+ */
+
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+
+/**
  * @brief Accumulate the X.25 CRC by adding one char at a time.
  *
  * The checksum function adds the hash of one char at a time to the
--- a/Module_Communication/MAVlink/include/protocol.h	Wed Mar 19 09:27:19 2014 +0000
+++ b/Module_Communication/MAVlink/include/protocol.h	Wed Mar 19 11:01:10 2014 +0000
@@ -6,6 +6,7 @@
 
 #include "mavlink_types.h"
 
+extern Serial pc;
 
 /**
  * @brief Initialize the communication stack
@@ -64,6 +65,9 @@
 static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length)
 {
     // This code part is the same for all messages;
+    //for extra seed in mavlink 1.0
+    static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
+    
     uint16_t checksum;
     msg->len = length;
     msg->sysid = system_id;
@@ -72,7 +76,8 @@
     msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq;
     mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1;
     checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
-    crc_accumulate(50, &checksum);
+    //for extra seed in mavlink 1.0
+    crc_accumulate(mavlink_message_crcs[msg->msgid], &checksum);
     
     msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
     msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
@@ -203,6 +208,9 @@
 {
     static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
 
+    // For crc calculation with extra seed in mavlink 1.0
+    //static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
+
     // Initializes only once, values keep unchanged after first initialization
     mavlink_parse_state_initialize(mavlink_get_channel_status(chan));
 
@@ -282,6 +290,10 @@
         break;
 
     case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
+    /* Add seed to checksum depending on message id */
+        //mavlink_update_checksum(rxmsg, mavlink_message_crcs[rxmsg->msgid]);
+        //pc.printf("Calculated Checksum : a %d b %d\n", rxmsg->ck_a, rxmsg->ck_b);
+        
         /*if (c != rxmsg->ck_a)
         {
             // Check first checksum byte