mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Common: fix Bitmask out-of-range values
This commit is contained in:
parent
963c9c93fe
commit
1a9bccaaa7
@ -20,9 +20,11 @@
|
|||||||
|
|
||||||
class Bitmask {
|
class Bitmask {
|
||||||
public:
|
public:
|
||||||
Bitmask(uint16_t numbits) :
|
Bitmask(uint16_t num_bits) :
|
||||||
numwords((numbits+31)/32) {
|
numbits(num_bits),
|
||||||
|
numwords((num_bits+31)/32) {
|
||||||
bits = new uint32_t[numwords];
|
bits = new uint32_t[numwords];
|
||||||
|
clearall();
|
||||||
}
|
}
|
||||||
~Bitmask(void) {
|
~Bitmask(void) {
|
||||||
delete[] bits;
|
delete[] bits;
|
||||||
@ -30,6 +32,10 @@ public:
|
|||||||
|
|
||||||
// set given bitnumber
|
// set given bitnumber
|
||||||
void set(uint16_t bit) {
|
void set(uint16_t bit) {
|
||||||
|
// ignore an invalid bit number
|
||||||
|
if (bit >= numbits) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
uint16_t word = bit/32;
|
uint16_t word = bit/32;
|
||||||
uint8_t ofs = bit & 0x1f;
|
uint8_t ofs = bit & 0x1f;
|
||||||
bits[word] |= (1U << ofs);
|
bits[word] |= (1U << ofs);
|
||||||
@ -37,9 +43,13 @@ public:
|
|||||||
|
|
||||||
// set all bits
|
// set all bits
|
||||||
void setall(void) {
|
void setall(void) {
|
||||||
for (uint16_t i=0; i<numwords; i++) {
|
// set all words to 111... except the last one.
|
||||||
|
for (uint16_t i=0; i<numwords-1; i++) {
|
||||||
bits[i] = 0xffffffff;
|
bits[i] = 0xffffffff;
|
||||||
}
|
}
|
||||||
|
// set most of the last word to 111.., leaving out-of-range bits to be 0
|
||||||
|
uint16_t num_valid_bits = numbits % 32;
|
||||||
|
bits[numwords-1] = (1 << num_valid_bits) - 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// clear given bitnumber
|
// clear given bitnumber
|
||||||
@ -51,9 +61,7 @@ public:
|
|||||||
|
|
||||||
// clear all bits
|
// clear all bits
|
||||||
void clearall(void) {
|
void clearall(void) {
|
||||||
for (uint16_t i=0; i<numwords; i++) {
|
memset(bits, 0, numwords*sizeof(bits[0]));
|
||||||
bits[i] = 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if given bitnumber is set
|
// return true if given bitnumber is set
|
||||||
@ -88,12 +96,13 @@ public:
|
|||||||
return sum;
|
return sum;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return number of bits available (may be slightly larger than number requested in constructor)
|
// return number of bits available
|
||||||
uint16_t size() const {
|
uint16_t size() const {
|
||||||
return numwords * 32;
|
return numbits;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
uint16_t numbits;
|
||||||
uint16_t numwords;
|
uint16_t numwords;
|
||||||
uint32_t *bits;
|
uint32_t *bits;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user