Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Javascript: Fix wrong crc calculation #940

Merged
merged 2 commits into from
Apr 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions generator/mavgen_javascript.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def generate_preamble(outf, msgs, args, xml):
${MAVHEAD}.x25Crc = function(buffer, crcIN) {

var bytes = buffer;
var crcOUT = crcIN || 0xffff;
var crcOUT = crcIN === undefined ? 0xffff : crcIN;
_.each(bytes, function(e) {
var tmp = e ^ (crcOUT & 0xff);
tmp = (tmp ^ (tmp << 4)) & 0xff;
Expand Down Expand Up @@ -846,7 +846,7 @@ def generate_mavlink_class(outf, msgs, xml):
var messageChecksum2 = ${MAVHEAD}.x25Crc([decoder.crc_extra], messageChecksum);

if ( receivedChecksum != messageChecksum2 ) {
throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got 0x' + receivedChecksum + ' checksum, calculated payload checksum as 0x'+messageChecksum2 );
throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got ' + receivedChecksum + ' checksum, calculated payload checksum as '+messageChecksum2 );
}

// now check the signature...
Expand Down
4 changes: 2 additions & 2 deletions generator/mavgen_javascript_stable.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def generate_preamble(outf, msgs, args, xml):
${MAVHEAD}.x25Crc = function(buffer, crcIN) {

var bytes = buffer;
var crcOUT = crcIN || 0xffff;
var crcOUT = crcIN === undefined ? 0xffff : crcIN;
_.each(bytes, function(e) {
var tmp = e ^ (crcOUT & 0xff);
tmp = (tmp ^ (tmp << 4)) & 0xff;
Expand Down Expand Up @@ -570,7 +570,7 @@ def generate_mavlink_class(outf, msgs, xml):
messageChecksum = ${MAVHEAD}.x25Crc([decoder.crc_extra], messageChecksum);

if ( receivedChecksum != messageChecksum ) {
throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got 0x' + receivedChecksum + ' checksum, calculated payload checksum as 0x'+messageChecksum );
throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got ' + receivedChecksum + ' checksum, calculated payload checksum as '+messageChecksum );
}

var paylen = jspack.CalcLength(decoder.format);
Expand Down
Loading