mirror of https://github.com/ArduPilot/ardupilot
Tools: removed assert calls
these waste flash space and do not do us any good
This commit is contained in:
parent
1f60eb68ec
commit
22c936140e
|
@ -310,7 +310,6 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr
|
|||
uint8_t received_unique_id[UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH];
|
||||
uint8_t received_unique_id_len = 0;
|
||||
for (; received_unique_id_len < (transfer->payload_len - (UniqueIDBitOffset / 8U)); received_unique_id_len++) {
|
||||
assert(received_unique_id_len < UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH);
|
||||
const uint8_t bit_offset = (uint8_t)(UniqueIDBitOffset + received_unique_id_len * 8U);
|
||||
(void) canardDecodeScalar(transfer, bit_offset, 8, false, &received_unique_id[received_unique_id_len]);
|
||||
}
|
||||
|
@ -333,7 +332,6 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr
|
|||
// Allocation complete - copying the allocated node ID from the message
|
||||
uint8_t allocated_node_id = 0;
|
||||
(void) canardDecodeScalar(transfer, 0, 7, false, &allocated_node_id);
|
||||
assert(allocated_node_id <= 127);
|
||||
|
||||
canardSetLocalNodeID(ins, allocated_node_id);
|
||||
}
|
||||
|
|
|
@ -417,7 +417,6 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr
|
|||
uint8_t received_unique_id[UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH];
|
||||
uint8_t received_unique_id_len = 0;
|
||||
for (; received_unique_id_len < (transfer->payload_len - (UniqueIDBitOffset / 8U)); received_unique_id_len++) {
|
||||
assert(received_unique_id_len < UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH);
|
||||
const uint8_t bit_offset = (uint8_t)(UniqueIDBitOffset + received_unique_id_len * 8U);
|
||||
(void) canardDecodeScalar(transfer, bit_offset, 8, false, &received_unique_id[received_unique_id_len]);
|
||||
}
|
||||
|
@ -443,7 +442,6 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr
|
|||
// Allocation complete - copying the allocated node ID from the message
|
||||
uint8_t allocated_node_id = 0;
|
||||
(void) canardDecodeScalar(transfer, 0, 7, false, &allocated_node_id);
|
||||
assert(allocated_node_id <= 127);
|
||||
|
||||
canardSetLocalNodeID(ins, allocated_node_id);
|
||||
printf("Node ID allocated: %d\n", allocated_node_id);
|
||||
|
@ -1212,12 +1210,6 @@ static void can_wait_node_id(void)
|
|||
uid_size = MaxLenOfUniqueIDInRequest;
|
||||
}
|
||||
|
||||
// Paranoia time
|
||||
assert(node_id_allocation_unique_id_offset < UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH);
|
||||
assert(uid_size <= MaxLenOfUniqueIDInRequest);
|
||||
assert(uid_size > 0);
|
||||
assert((uid_size + node_id_allocation_unique_id_offset) <= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_UNIQUE_ID_MAX_LENGTH);
|
||||
|
||||
memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size);
|
||||
|
||||
// Broadcasting the request
|
||||
|
|
Loading…
Reference in New Issue