Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
gnsstk::PackedNavBits Class Reference

Detailed Description

Definition at line 70 of file PackedNavBits.hpp.

#include <PackedNavBits.hpp>

Public Types

enum  ParityStatus { psUnknown, psPassed, psFailed }
 

Public Member Functions

template<size_t N>
void addBitset (const std::bitset< N > &newbits)
 
void addDataVec (const std::vector< uint8_t > &data, unsigned numBits)
 
void addDoubleSemiCircles (const double radians, const int numBits, const int power2)
 
void addLong (const long value, const int numBits, const int scale)
 
void addPackedNavBits (const PackedNavBits &pnb)
 
void addSignedDouble (const double value, const int numBits, const int power2)
 
void addString (const std::string String, const int numChars)
 
void addUnsignedDouble (const double value, const int numBits, const int power2)
 
void addUnsignedLong (const unsigned long value, const int numBits, const int scale)
 
bool asBool (const unsigned bitNum) const
 
double asDoubleSemiCircles (const int startBit, const int numBits, const int power2) const
 
double asDoubleSemiCircles (const unsigned startBit1, const unsigned numBits1, const unsigned startBit2, const unsigned numBits2, const int power2) const
 
double asDoubleSemiCircles (const unsigned startBits[], const unsigned numBits[], const unsigned len, const int power2) const
 
long asLong (const int startBit, const int numBits, const int scale) const
 
long asLong (const unsigned startBit1, const unsigned numBits1, const unsigned startBit2, const unsigned numBits2, const int scale) const
 
long asLong (const unsigned startBits[], const unsigned numBits[], const unsigned len, const int scale) const
 
double asSignedDouble (const int startBit, const int numBits, const int power2) const
 
double asSignedDouble (const unsigned startBit1, const unsigned numBits1, const unsigned startBit2, const unsigned numBits2, const int power2) const
 
double asSignedDouble (const unsigned startBits[], const unsigned numBits[], const unsigned len, const int power2) const
 
double asSignMagDouble (const int startBit, const int numBits, const int power2) const
 
double asSignMagDoubleSemiCircles (const int startBit, const int numBits, const int power2) const
 
long asSignMagLong (const int startBit, const int numBits, const int scale) const
 
std::string asString (const int startBit, const int numChars) const
 
double asUnsignedDouble (const int startBit, const int numBits, const int power2) const
 
double asUnsignedDouble (const unsigned startBit1, const unsigned numBits1, const unsigned startBit2, const unsigned numBits2, const int power2) const
 
double asUnsignedDouble (const unsigned startBits[], const unsigned numBits[], const unsigned len, const int power2) const
 
unsigned long asUnsignedLong (const int startBit, const int numBits, const int scale) const
 
unsigned long asUnsignedLong (const unsigned startBit1, const unsigned numBits1, const unsigned startBit2, const unsigned numBits2, const int scale) const
 
unsigned long asUnsignedLong (const unsigned startBits[], const unsigned numBits[], const unsigned len, const int scale) const
 
void clearBits ()
 
PackedNavBitsclone () const
 
void copyBits (const PackedNavBits &src, const short startBit=0, const short endBit=-1)
 
void dump (std::ostream &s=std::cout) const noexcept
 
const std::vector< bool > & getBits () const
 
NavID getNavID () const
 
size_t getNumBits () const
 
ObsID getobsID () const
 
std::string getRxID () const
 
SatID getsatSys () const
 
CommonTime getTransmitTime () const
 
void insertUnsignedLong (const unsigned long value, const int startBit, const int numBits, const int scale=1)
 
void invert ()
 
bool isXmitCoerced () const
 
bool match (const PackedNavBits &right, const short startBit=0, const short endBit=-1, const unsigned flagBits=mmALL) const
 
bool matchBits (const PackedNavBits &right, const short startBit=0, const short endBit=-1) const
 
bool matchMetaData (const PackedNavBits &right, const unsigned flagBits=mmALL) const
 
bool operator< (const PackedNavBits &right) const
 
bool operator== (const PackedNavBits &right) const
 
int outputPackedBits (std::ostream &s=std::cout, const short numPerLine=4, const char delimiter=' ', const short numBitsPerWord=32) const
 
 PackedNavBits ()
 empty constructor More...
 
 PackedNavBits (const PackedNavBits &right)
 
 PackedNavBits (const SatID &satSysArg, const ObsID &obsIDArg, const CommonTime &transmitTimeArg)
 explicit constructor More...
 
 PackedNavBits (const SatID &satSysArg, const ObsID &obsIDArg, const NavID &navIDArg, const std::string rxString, const CommonTime &transmitTimeArg)
 explicit constructor More...
 
 PackedNavBits (const SatID &satSysArg, const ObsID &obsIDArg, const NavID &navIDArg, const std::string rxString, const CommonTime &transmitTimeArg, unsigned numBits, bool fillValue)
 explicit constructor More...
 
 PackedNavBits (const SatID &satSysArg, const ObsID &obsIDArg, const std::string rxString, const CommonTime &transmitTimeArg)
 explicit constructor More...
 
void rawBitInput (const std::string inString)
 
void reset_num_bits (const int new_bits_used=0)
 
void setNavID (const NavID &navIDArg)
 
void setObsID (const ObsID &obsIDArg)
 
void setRxID (const std::string rxString)
 
void setSatID (const SatID &satSysArg)
 
void setTime (const CommonTime &transmitTimeArg)
 
void setXmitCoerced (bool tf=true)
 
void trimsize ()
 

Static Public Member Functions

static double asSignedDouble (const std::vector< unsigned > &startBits, const std::vector< unsigned > &numBits, const std::vector< unsigned > &whichSF, const std::vector< PackedNavBitsPtr > &bits, const int power2)
 
static double asUnsignedDouble (const std::vector< unsigned > &startBits, const std::vector< unsigned > &numBits, const std::vector< unsigned > &whichSF, const std::vector< PackedNavBitsPtr > &bits, const int power2)
 

Public Attributes

ParityStatus parityStatus
 

Static Public Attributes

static const unsigned int mmALL = 0xFFFF
 
static const unsigned int mmNAV = 0x0010
 
static const unsigned int mmNONE = 0x0000
 
static const unsigned int mmOBS = 0x0004
 
static const unsigned int mmRX = 0x0008
 
static const unsigned int mmSAT = 0x0002
 
static const unsigned int mmTIME = 0x0001
 

Private Member Functions

void addUint64_t (const uint64_t value, const int numBits)
 
uint64_t asUint64_t (const int startBit, const int numBits) const
 
double ScaleValue (const double value, const int power2) const
 
int64_t SignExtend (const int startBit, const int numBits) const
 

Private Attributes

std::vector< bool > bits
 
int bits_used
 
NavID navID
 
ObsID obsID
 
std::string rxID
 
SatID satSys
 
CommonTime transmitTime
 
bool xMitCoerced
 

Member Enumeration Documentation

◆ ParityStatus

Indicate whether parity/CRC/whatever checking has been performed and whether that check passed or failed on this subframe/message.

Enumerator
psUnknown 

Parity/CRC check has not been performed.

psPassed 

Parity/CRC check was performed and passed.

psFailed 

Parity/CRC check was performed and failed.

Definition at line 76 of file PackedNavBits.hpp.

Constructor & Destructor Documentation

◆ PackedNavBits() [1/6]

gnsstk::PackedNavBits::PackedNavBits ( )

empty constructor

Definition at line 57 of file PackedNavBits.cpp.

◆ PackedNavBits() [2/6]

gnsstk::PackedNavBits::PackedNavBits ( const SatID satSysArg,
const ObsID obsIDArg,
const CommonTime transmitTimeArg 
)

explicit constructor

Definition at line 67 of file PackedNavBits.cpp.

◆ PackedNavBits() [3/6]

gnsstk::PackedNavBits::PackedNavBits ( const SatID satSysArg,
const ObsID obsIDArg,
const std::string  rxString,
const CommonTime transmitTimeArg 
)

explicit constructor

Definition at line 82 of file PackedNavBits.cpp.

◆ PackedNavBits() [4/6]

gnsstk::PackedNavBits::PackedNavBits ( const SatID satSysArg,
const ObsID obsIDArg,
const NavID navIDArg,
const std::string  rxString,
const CommonTime transmitTimeArg 
)

explicit constructor

Definition at line 99 of file PackedNavBits.cpp.

◆ PackedNavBits() [5/6]

gnsstk::PackedNavBits::PackedNavBits ( const SatID satSysArg,
const ObsID obsIDArg,
const NavID navIDArg,
const std::string  rxString,
const CommonTime transmitTimeArg,
unsigned  numBits,
bool  fillValue 
)

explicit constructor

Definition at line 119 of file PackedNavBits.cpp.

◆ PackedNavBits() [6/6]

gnsstk::PackedNavBits::PackedNavBits ( const PackedNavBits right)

Definition at line 140 of file PackedNavBits.cpp.

Member Function Documentation

◆ addBitset()

template<size_t N>
void gnsstk::PackedNavBits::addBitset ( const std::bitset< N > &  newbits)
inline

Pack a bitset. This is done by converting it first to a string of 0 and 1 characters which are then treated as an array that is appended to the end of the bits vector. Not entirely sure if this is faster than iterating.

Parameters
[in]newbitsThe bitset containing the data to append to the PackedNavBits data.

Definition at line 446 of file PackedNavBits.hpp.

◆ addDataVec()

void gnsstk::PackedNavBits::addDataVec ( const std::vector< uint8_t > &  data,
unsigned  numBits 
)

Pack a vector of bytes.

Parameters
[in]dataThe vector of bytes to append to the packed nav bits.
[in]numBitsThe actual number of bits to add. Bits are added starting with the MSB of data[0].
Note
The contents of data are assumed to be left-aligned and right padded, meaning that if you have have a vector of 8 bytes and you want to add 60 bits, data[7] is expected to contain the bits in the 4 MSBs and not in the 4 LSBs.
Exceptions
InvalidParameterif numBits is > 8*data.size().

Definition at line 740 of file PackedNavBits.cpp.

◆ addDoubleSemiCircles()

void gnsstk::PackedNavBits::addDoubleSemiCircles ( const double  radians,
const int  numBits,
const int  power2 
)

Pack a double with units of semicircles

Exceptions
InvalidParameter

Definition at line 680 of file PackedNavBits.cpp.

◆ addLong()

void gnsstk::PackedNavBits::addLong ( const long  value,
const int  numBits,
const int  scale 
)

Pack a signed long integer

Exceptions
InvalidParameter

Definition at line 629 of file PackedNavBits.cpp.

◆ addPackedNavBits()

void gnsstk::PackedNavBits::addPackedNavBits ( const PackedNavBits pnb)
Exceptions
InvalidParameter

Definition at line 771 of file PackedNavBits.cpp.

◆ addSignedDouble()

void gnsstk::PackedNavBits::addSignedDouble ( const double  value,
const int  numBits,
const int  power2 
)

Pack a signed double

Exceptions
InvalidParameter

Definition at line 662 of file PackedNavBits.cpp.

◆ addString()

void gnsstk::PackedNavBits::addString ( const std::string  String,
const int  numChars 
)

Pack a string. Characters in String limited to those defined in IS-GPS-200 Section 20.3.3.5.1.8 If numChars < length of String only, chars 1..numChars will be added. If numChars > length of String, blanks will be added at the end.

Parameters
[in]numCharsrepresents number of chars (8 bits each) to add to PackedBits.
Exceptions
InvalidParameter

Definition at line 699 of file PackedNavBits.cpp.

◆ addUint64_t()

void gnsstk::PackedNavBits::addUint64_t ( const uint64_t  value,
const int  numBits 
)
private

Pack the bits

Definition at line 783 of file PackedNavBits.cpp.

◆ addUnsignedDouble()

void gnsstk::PackedNavBits::addUnsignedDouble ( const double  value,
const int  numBits,
const int  power2 
)

Pack an unsigned double

Exceptions
InvalidParameter

Definition at line 648 of file PackedNavBits.cpp.

◆ addUnsignedLong()

void gnsstk::PackedNavBits::addUnsignedLong ( const unsigned long  value,
const int  numBits,
const int  scale 
)

Pack an unsigned long integer

Exceptions
InvalidParameter

Definition at line 613 of file PackedNavBits.cpp.

◆ asBool()

bool gnsstk::PackedNavBits::asBool ( const unsigned  bitNum) const

Definition at line 606 of file PackedNavBits.cpp.

◆ asDoubleSemiCircles() [1/3]

double gnsstk::PackedNavBits::asDoubleSemiCircles ( const int  startBit,
const int  numBits,
const int  power2 
) const

Definition at line 304 of file PackedNavBits.cpp.

◆ asDoubleSemiCircles() [2/3]

double gnsstk::PackedNavBits::asDoubleSemiCircles ( const unsigned  startBit1,
const unsigned  numBits1,
const unsigned  startBit2,
const unsigned  numBits2,
const int  power2 
) const

Unpack a floating point number split into two pieces, converting from semi-circles to radians.

Warning
Be careful about what order you specify the parameters in.
Note
This prototype obviates constructing an array before calling.
Parameters
[in]startBit1The 0-indexed first bit of the MSBs.
[in]numBits1The number of MSBs.
[in]startBit2The 0-indexed first bit of the LSBs.
[in]numBits2The number of LSBs.
[in]power2The result is multiplied by 2^(power2) before returning.
Returns
The decoded value.

Definition at line 595 of file PackedNavBits.cpp.

◆ asDoubleSemiCircles() [3/3]

double gnsstk::PackedNavBits::asDoubleSemiCircles ( const unsigned  startBits[],
const unsigned  numBits[],
const unsigned  len,
const int  power2 
) const

Definition at line 585 of file PackedNavBits.cpp.

◆ asLong() [1/3]

long gnsstk::PackedNavBits::asLong ( const int  startBit,
const int  numBits,
const int  scale 
) const

Definition at line 275 of file PackedNavBits.cpp.

◆ asLong() [2/3]

long gnsstk::PackedNavBits::asLong ( const unsigned  startBit1,
const unsigned  numBits1,
const unsigned  startBit2,
const unsigned  numBits2,
const int  scale 
) const

Unpack an signed long integer split into two pieces.

Warning
Be careful about what order you specify the parameters in.
Note
This prototype obviates constructing an array before calling.
Parameters
[in]startBit1The 0-indexed first bit of the MSBs.
[in]numBits1The number of MSBs.
[in]startBit2The 0-indexed first bit of the LSBs.
[in]numBits2The number of LSBs.
[in]scaleA number to multiply the bits by before returning.
Returns
The decoded value.

Definition at line 438 of file PackedNavBits.cpp.

◆ asLong() [3/3]

long gnsstk::PackedNavBits::asLong ( const unsigned  startBits[],
const unsigned  numBits[],
const unsigned  len,
const int  scale 
) const

Definition at line 415 of file PackedNavBits.cpp.

◆ asSignedDouble() [1/4]

double gnsstk::PackedNavBits::asSignedDouble ( const int  startBit,
const int  numBits,
const int  power2 
) const

Definition at line 293 of file PackedNavBits.cpp.

◆ asSignedDouble() [2/4]

double gnsstk::PackedNavBits::asSignedDouble ( const std::vector< unsigned > &  startBits,
const std::vector< unsigned > &  numBits,
const std::vector< unsigned > &  whichSF,
const std::vector< PackedNavBitsPtr > &  bits,
const int  power2 
)
static

Unpack a floating point number split into an arbitrary number of pieces. The startBits, numBits and whichSF parameters must all have the same size, however in the interest of performance, no checking is done to make sure that is the case. Additionally, the values in whichSF must refer to valid indices of the bits vector, which also is not validated. The elements of startBits, numBits and whichSF must correspond to the same segment for a given vector index, and must be in order of MSB to LSB.

Note
This prototype is intended to be used when the encoded value spans multiple subframes and thus multiple PackedNavBits objects.
Parameters
[in]startBitsThe 0-indexed first bit of each segment.
[in]numBitsThe number of bits for each segment.
[in]whichSFThe index into bits that pertains to the segment.
[in]bitsThe set of PackedNavBits objects used to construct the value being decoded.
[in]power2The result is multiplied by 2^(power2) before returning.
Returns
The decoded value.

Definition at line 526 of file PackedNavBits.cpp.

◆ asSignedDouble() [3/4]

double gnsstk::PackedNavBits::asSignedDouble ( const unsigned  startBit1,
const unsigned  numBits1,
const unsigned  startBit2,
const unsigned  numBits2,
const int  power2 
) const

Unpack a floating point number split into two pieces.

Warning
Be careful about what order you specify the parameters in.
Note
This prototype obviates constructing an array before calling.
Parameters
[in]startBit1The 0-indexed first bit of the MSBs.
[in]numBits1The number of MSBs.
[in]startBit2The 0-indexed first bit of the LSBs.
[in]numBits2The number of LSBs.
[in]power2The result is multiplied by 2^(power2) before returning.
Returns
The decoded value.

Definition at line 567 of file PackedNavBits.cpp.

◆ asSignedDouble() [4/4]

double gnsstk::PackedNavBits::asSignedDouble ( const unsigned  startBits[],
const unsigned  numBits[],
const unsigned  len,
const int  power2 
) const

Definition at line 500 of file PackedNavBits.cpp.

◆ asSignMagDouble()

double gnsstk::PackedNavBits::asSignMagDouble ( const int  startBit,
const int  numBits,
const int  power2 
) const

Definition at line 331 of file PackedNavBits.cpp.

◆ asSignMagDoubleSemiCircles()

double gnsstk::PackedNavBits::asSignMagDoubleSemiCircles ( const int  startBit,
const int  numBits,
const int  power2 
) const

Definition at line 349 of file PackedNavBits.cpp.

◆ asSignMagLong()

long gnsstk::PackedNavBits::asSignMagLong ( const int  startBit,
const int  numBits,
const int  scale 
) const

Definition at line 313 of file PackedNavBits.cpp.

◆ asString()

std::string gnsstk::PackedNavBits::asString ( const int  startBit,
const int  numChars 
) const

Definition at line 358 of file PackedNavBits.cpp.

◆ asUint64_t()

uint64_t gnsstk::PackedNavBits::asUint64_t ( const int  startBit,
const int  numBits 
) const
private

Unpack the bits

Exceptions
InvalidParameter

Definition at line 246 of file PackedNavBits.cpp.

◆ asUnsignedDouble() [1/4]

double gnsstk::PackedNavBits::asUnsignedDouble ( const int  startBit,
const int  numBits,
const int  power2 
) const

Definition at line 282 of file PackedNavBits.cpp.

◆ asUnsignedDouble() [2/4]

double gnsstk::PackedNavBits::asUnsignedDouble ( const std::vector< unsigned > &  startBits,
const std::vector< unsigned > &  numBits,
const std::vector< unsigned > &  whichSF,
const std::vector< PackedNavBitsPtr > &  bits,
const int  power2 
)
static

Unpack a floating point number split into an arbitrary number of pieces. The startBits, numBits and whichSF parameters must all have the same size, however in the interest of performance, no checking is done to make sure that is the case. Additionally, the values in whichSF must refer to valid indices of the bits vector, which also is not validated. The elements of startBits, numBits and whichSF must correspond to the same segment for a given vector index, and must be in order of MSB to LSB.

Note
This prototype is intended to be used when the encoded value spans multiple subframes and thus multiple PackedNavBits objects.
Parameters
[in]startBitsThe 0-indexed first bit of each segment.
[in]numBitsThe number of bits for each segment.
[in]whichSFThe index into bits that pertains to the segment.
[in]bitsThe set of PackedNavBits objects used to construct the value being decoded.
[in]power2The result is multiplied by 2^(power2) before returning.
Returns
The decoded value.

Definition at line 547 of file PackedNavBits.cpp.

◆ asUnsignedDouble() [3/4]

double gnsstk::PackedNavBits::asUnsignedDouble ( const unsigned  startBit1,
const unsigned  numBits1,
const unsigned  startBit2,
const unsigned  numBits2,
const int  power2 
) const

Unpack a positive-only floating point number split into two pieces.

Warning
Be careful about what order you specify the parameters in.
Note
This prototype obviates constructing an array before calling.
Parameters
[in]startBit1The 0-indexed first bit of the MSBs.
[in]numBits1The number of MSBs.
[in]startBit2The 0-indexed first bit of the LSBs.
[in]numBits2The number of LSBs.
[in]power2The result is multiplied by 2^(power2) before returning.
Returns
The decoded value.

Definition at line 482 of file PackedNavBits.cpp.

◆ asUnsignedDouble() [4/4]

double gnsstk::PackedNavBits::asUnsignedDouble ( const unsigned  startBits[],
const unsigned  numBits[],
const unsigned  len,
const int  power2 
) const

Definition at line 454 of file PackedNavBits.cpp.

◆ asUnsignedLong() [1/3]

unsigned long gnsstk::PackedNavBits::asUnsignedLong ( const int  startBit,
const int  numBits,
const int  scale 
) const

Definition at line 265 of file PackedNavBits.cpp.

◆ asUnsignedLong() [2/3]

unsigned long gnsstk::PackedNavBits::asUnsignedLong ( const unsigned  startBit1,
const unsigned  numBits1,
const unsigned  startBit2,
const unsigned  numBits2,
const int  scale 
) const

Unpack an unsigned long integer split into two pieces.

Warning
Be careful about what order you specify the parameters in.
Note
This prototype obviates constructing an array before calling.
Parameters
[in]startBit1The 0-indexed first bit of the MSBs.
[in]numBits1The number of MSBs.
[in]startBit2The 0-indexed first bit of the LSBs.
[in]numBits2The number of LSBs.
[in]scaleA number to multiply the bits by before returning.
Returns
The decoded value.

Definition at line 399 of file PackedNavBits.cpp.

◆ asUnsignedLong() [3/3]

unsigned long gnsstk::PackedNavBits::asUnsignedLong ( const unsigned  startBits[],
const unsigned  numBits[],
const unsigned  len,
const int  scale 
) const

Definition at line 374 of file PackedNavBits.cpp.

◆ clearBits()

void gnsstk::PackedNavBits::clearBits ( )

Definition at line 209 of file PackedNavBits.cpp.

◆ clone()

PackedNavBits * gnsstk::PackedNavBits::clone ( ) const

Definition at line 174 of file PackedNavBits.cpp.

◆ copyBits()

void gnsstk::PackedNavBits::copyBits ( const PackedNavBits src,
const short  startBit = 0,
const short  endBit = -1 
)

Bit wise copy from another PackecNavBits. None of the meta-data (transmit time, SatID, ObsID) will be changed. This method is intended for use between two PackedNavBits objecst that are ALREADY the same size (in bits). Yes, we could define a copy that would account for the difference, but the pre-existing model for PNB is that the bits_used variable records the # of bits used as items are added to the end of the bit array. I didn't want copyBits( ) to confuse that model by modifying bits_used.

Exceptions
InvalidParameterif called using two objects that are NOT the same size.

Bit wise copy from another PackecNavBits. None of the meta-data (transmit time, SatID, ObsID) will be changed.

Definition at line 864 of file PackedNavBits.cpp.

◆ dump()

void gnsstk::PackedNavBits::dump ( std::ostream &  s = std::cout) const
noexcept

Definition at line 966 of file PackedNavBits.cpp.

◆ getBits()

const std::vector<bool>& gnsstk::PackedNavBits::getBits ( ) const
inline

Definition at line 622 of file PackedNavBits.hpp.

◆ getNavID()

NavID gnsstk::PackedNavBits::getNavID ( ) const

Definition at line 225 of file PackedNavBits.cpp.

◆ getNumBits()

size_t gnsstk::PackedNavBits::getNumBits ( ) const

Definition at line 240 of file PackedNavBits.cpp.

◆ getobsID()

ObsID gnsstk::PackedNavBits::getobsID ( ) const

Definition at line 215 of file PackedNavBits.cpp.

◆ getRxID()

std::string gnsstk::PackedNavBits::getRxID ( ) const

Definition at line 230 of file PackedNavBits.cpp.

◆ getsatSys()

SatID gnsstk::PackedNavBits::getsatSys ( ) const

Definition at line 220 of file PackedNavBits.cpp.

◆ getTransmitTime()

CommonTime gnsstk::PackedNavBits::getTransmitTime ( ) const

Definition at line 235 of file PackedNavBits.cpp.

◆ insertUnsignedLong()

void gnsstk::PackedNavBits::insertUnsignedLong ( const unsigned long  value,
const int  startBit,
const int  numBits,
const int  scale = 1 
)

This method is not typically used in production; however it is used in test support. It assumes the PNB object is already created and is already sized to hold at least (startBit+numBits) bits. If this is not true, an exception is thrown. It overwrites the data that is already present with the provided value / scale. If value / scale is too large to fit in numBits, then an exception is thrown.

Exceptions
InvalidParameter

Definition at line 889 of file PackedNavBits.cpp.

◆ invert()

void gnsstk::PackedNavBits::invert ( )

Bitwise invert contents of this object.

Definition at line 841 of file PackedNavBits.cpp.

◆ isXmitCoerced()

bool gnsstk::PackedNavBits::isXmitCoerced ( ) const
inline

Definition at line 620 of file PackedNavBits.hpp.

◆ match()

bool gnsstk::PackedNavBits::match ( const PackedNavBits right,
const short  startBit = 0,
const short  endBit = -1,
const unsigned  flagBits = mmALL 
) const

Definition at line 1079 of file PackedNavBits.cpp.

◆ matchBits()

bool gnsstk::PackedNavBits::matchBits ( const PackedNavBits right,
const short  startBit = 0,
const short  endBit = -1 
) const

Definition at line 1116 of file PackedNavBits.cpp.

◆ matchMetaData()

bool gnsstk::PackedNavBits::matchMetaData ( const PackedNavBits right,
const unsigned  flagBits = mmALL 
) const

Definition at line 1089 of file PackedNavBits.cpp.

◆ operator<()

bool gnsstk::PackedNavBits::operator< ( const PackedNavBits right) const

The less than operator is defined in order to support use with the NavFilter classes. The idea is to provide a "sort" for bits contained in the class. Matching strings will fail both a < b and b < a; however, in the process all matching strings can be sorted into sets and the "winner" determined.

Definition at line 813 of file PackedNavBits.cpp.

◆ operator==()

bool gnsstk::PackedNavBits::operator== ( const PackedNavBits right) const

Definition at line 1072 of file PackedNavBits.cpp.

◆ outputPackedBits()

int gnsstk::PackedNavBits::outputPackedBits ( std::ostream &  s = std::cout,
const short  numPerLine = 4,
const char  delimiter = ' ',
const short  numBitsPerWord = 32 
) const

Definition at line 1028 of file PackedNavBits.cpp.

◆ rawBitInput()

void gnsstk::PackedNavBits::rawBitInput ( const std::string  inString)

Raw bit input This function is intended as a test-support function. It assumes a string of the form

0xABCDABCD 0xABCDABCD 0xABCDABCD

where

is the number of bits to expect in the remainder

of the line. 0xABCDABCD are each 32-bit unsigned hex numbers, left justified. The number of bits needs to match or exceed ### The function returns if the read is succeessful. Otherwise,the function throws an exception

Exceptions
InvalidParameter

Definition at line 1142 of file PackedNavBits.cpp.

◆ reset_num_bits()

void gnsstk::PackedNavBits::reset_num_bits ( const int  new_bits_used = 0)

Reset number of bits

Definition at line 932 of file PackedNavBits.cpp.

◆ ScaleValue()

double gnsstk::PackedNavBits::ScaleValue ( const double  value,
const int  power2 
) const
private

Scales doubles by their corresponding scale factor

Definition at line 957 of file PackedNavBits.cpp.

◆ setNavID()

void gnsstk::PackedNavBits::setNavID ( const NavID navIDArg)

Definition at line 191 of file PackedNavBits.cpp.

◆ setObsID()

void gnsstk::PackedNavBits::setObsID ( const ObsID obsIDArg)

Definition at line 185 of file PackedNavBits.cpp.

◆ setRxID()

void gnsstk::PackedNavBits::setRxID ( const std::string  rxString)

Definition at line 197 of file PackedNavBits.cpp.

◆ setSatID()

void gnsstk::PackedNavBits::setSatID ( const SatID satSysArg)

Definition at line 179 of file PackedNavBits.cpp.

◆ setTime()

void gnsstk::PackedNavBits::setTime ( const CommonTime transmitTimeArg)

Definition at line 203 of file PackedNavBits.cpp.

◆ setXmitCoerced()

void gnsstk::PackedNavBits::setXmitCoerced ( bool  tf = true)
inline

Definition at line 619 of file PackedNavBits.hpp.

◆ SignExtend()

int64_t gnsstk::PackedNavBits::SignExtend ( const int  startBit,
const int  numBits 
) const
private

Extend the sign bit for signed values

Definition at line 944 of file PackedNavBits.cpp.

◆ trimsize()

void gnsstk::PackedNavBits::trimsize ( )

Definition at line 938 of file PackedNavBits.cpp.

Member Data Documentation

◆ bits

std::vector<bool> gnsstk::PackedNavBits::bits
private

Holds the packed data

Definition at line 636 of file PackedNavBits.hpp.

◆ bits_used

int gnsstk::PackedNavBits::bits_used
private

Definition at line 637 of file PackedNavBits.hpp.

◆ mmALL

const unsigned int gnsstk::PackedNavBits::mmALL = 0xFFFF
static

Definition at line 492 of file PackedNavBits.hpp.

◆ mmNAV

const unsigned int gnsstk::PackedNavBits::mmNAV = 0x0010
static

Definition at line 491 of file PackedNavBits.hpp.

◆ mmNONE

const unsigned int gnsstk::PackedNavBits::mmNONE = 0x0000
static

Definition at line 493 of file PackedNavBits.hpp.

◆ mmOBS

const unsigned int gnsstk::PackedNavBits::mmOBS = 0x0004
static

Definition at line 489 of file PackedNavBits.hpp.

◆ mmRX

const unsigned int gnsstk::PackedNavBits::mmRX = 0x0008
static

Definition at line 490 of file PackedNavBits.hpp.

◆ mmSAT

const unsigned int gnsstk::PackedNavBits::mmSAT = 0x0002
static

Definition at line 488 of file PackedNavBits.hpp.

◆ mmTIME

const unsigned int gnsstk::PackedNavBits::mmTIME = 0x0001
static

Definition at line 487 of file PackedNavBits.hpp.

◆ navID

NavID gnsstk::PackedNavBits::navID
private

Defines the navigation message tracked

Definition at line 633 of file PackedNavBits.hpp.

◆ obsID

ObsID gnsstk::PackedNavBits::obsID
private

Defines carrier and code tracked

Definition at line 632 of file PackedNavBits.hpp.

◆ parityStatus

ParityStatus gnsstk::PackedNavBits::parityStatus

Indicate the status of parity/CRC checking. Must be explicitly set after construction, no parity checking is supported in this class.

Definition at line 628 of file PackedNavBits.hpp.

◆ rxID

std::string gnsstk::PackedNavBits::rxID
private

Defines the receiver that collected the data

Definition at line 634 of file PackedNavBits.hpp.

◆ satSys

SatID gnsstk::PackedNavBits::satSys
private

System ID (based on RINEX defintions

Definition at line 631 of file PackedNavBits.hpp.

◆ transmitTime

CommonTime gnsstk::PackedNavBits::transmitTime
private

Time nav message is transmitted

Definition at line 635 of file PackedNavBits.hpp.

◆ xMitCoerced

bool gnsstk::PackedNavBits::xMitCoerced
private

Used to indicate that the transmit time is NOT directly derived from the SOW in the message

Definition at line 639 of file PackedNavBits.hpp.


The documentation for this class was generated from the following files:


gnsstk
Author(s):
autogenerated on Wed Oct 25 2023 02:40:45