Go to the source code of this file.
Classes | |
struct | mavlink_sha256_ctx |
Macros | |
#define | A m->counter[0] |
#define | B m->counter[1] |
#define | C m->counter[2] |
#define | Ch(x, y, z) (((x) & (y)) ^ ((~(x)) & (z))) |
#define | D m->counter[3] |
#define | E m->counter[4] |
#define | F m->counter[5] |
#define | G m->counter[6] |
#define | H m->counter[7] |
#define | Maj(x, y, z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z))) |
#define | MAVLINK_HELPER |
#define | ROTR(x, n) (((x)>>(n)) | ((x) << (32 - (n)))) |
#define | Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22)) |
#define | sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3)) |
#define | Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25)) |
#define | sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10)) |
Functions | |
static void | mavlink_sha256_calc (mavlink_sha256_ctx *m, uint32_t *in) |
MAVLINK_HELPER void | mavlink_sha256_final_48 (mavlink_sha256_ctx *m, uint8_t result[6]) |
MAVLINK_HELPER void | mavlink_sha256_init (mavlink_sha256_ctx *m) |
MAVLINK_HELPER void | mavlink_sha256_update (mavlink_sha256_ctx *m, const void *v, uint32_t len) |
Variables | |
static const uint32_t | mavlink_sha256_constant_256 [64] |
#define A m->counter[0] |
Definition at line 72 of file mavlink_sha256.h.
#define B m->counter[1] |
Definition at line 73 of file mavlink_sha256.h.
#define C m->counter[2] |
Definition at line 74 of file mavlink_sha256.h.
#define Ch | ( | x, | |
y, | |||
z | |||
) | (((x) & (y)) ^ ((~(x)) & (z))) |
Definition at line 62 of file mavlink_sha256.h.
#define D m->counter[3] |
Definition at line 75 of file mavlink_sha256.h.
#define E m->counter[4] |
Definition at line 76 of file mavlink_sha256.h.
#define F m->counter[5] |
Definition at line 77 of file mavlink_sha256.h.
#define G m->counter[6] |
Definition at line 78 of file mavlink_sha256.h.
#define H m->counter[7] |
Definition at line 79 of file mavlink_sha256.h.
#define Maj | ( | x, | |
y, | |||
z | |||
) | (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z))) |
Definition at line 63 of file mavlink_sha256.h.
#define MAVLINK_HELPER |
Definition at line 50 of file mavlink_sha256.h.
#define ROTR | ( | x, | |
n | |||
) | (((x)>>(n)) | ((x) << (32 - (n)))) |
Definition at line 65 of file mavlink_sha256.h.
Definition at line 67 of file mavlink_sha256.h.
Definition at line 69 of file mavlink_sha256.h.
Definition at line 68 of file mavlink_sha256.h.
Definition at line 70 of file mavlink_sha256.h.
|
inlinestatic |
Definition at line 114 of file mavlink_sha256.h.
MAVLINK_HELPER void mavlink_sha256_final_48 | ( | mavlink_sha256_ctx * | m, |
uint8_t | result[6] | ||
) |
Definition at line 201 of file mavlink_sha256.h.
MAVLINK_HELPER void mavlink_sha256_init | ( | mavlink_sha256_ctx * | m | ) |
Definition at line 100 of file mavlink_sha256.h.
MAVLINK_HELPER void mavlink_sha256_update | ( | mavlink_sha256_ctx * | m, |
const void * | v, | ||
uint32_t | len | ||
) |
Definition at line 161 of file mavlink_sha256.h.
|
static |
Definition at line 81 of file mavlink_sha256.h.