Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rokubimini::serial::RokubiminiSerialImpl Class Reference

The Rokubimini Serial Implementation class. More...

#include <RokubiminiSerialImpl.hpp>

Public Member Functions

bool firmwareUpdate (const std::string &filePath)
 Updates the firmware of the device. More...
 
bool getForceTorqueSamplingRate (int &samplingRate)
 Gets the force torque sampling rate of the device. More...
 
std::string getName () const
 Accessor for device name. More...
 
void getReading (rokubimini::Reading &reading)
 Gets the internal reading variable. More...
 
bool getSerialNumber (unsigned int &serialNumber)
 Accessor for device serial number. More...
 
bool hasFrameSync ()
 Returns if there is frame synchronization with the device. More...
 
bool init ()
 This method initializes internal variables and the device for communication. It connects to the serial-port. More...
 
bool isRunning ()
 Returns if the serial driver is running. More...
 
bool loadConfig ()
 Loads the configuration of the device. More...
 
bool printUserConfig ()
 Prints all the user configurable parameters. More...
 
 RokubiminiSerialImpl ()=delete
 Default constructor is deleted. More...
 
 RokubiminiSerialImpl (const std::string &name, const std::string &port, const std::uint32_t &baudRate)
 Custom constructor for the RokubiminiSerialImpl class. More...
 
bool saveConfigParameter ()
 Saves the current configuration to the device. More...
 
bool setAccelerationFilter (const unsigned int filter)
 Sets an acceleration filter to the device. More...
 
bool setAccelerationRange (const unsigned int range)
 Sets an acceleration range to the device. More...
 
bool setAngularRateFilter (const unsigned int filter)
 Sets an angular rate filter to the device. More...
 
bool setAngularRateRange (const unsigned int range)
 Sets an angular rate range to the device. More...
 
bool setCommunicationSetup (const configuration::SensorConfiguration &sensorConfiguration, const uint8_t &dataFormat, const uint32_t &baudRate)
 Sets communication setup for the device. This includes setting the temperature compensation, the matrix calibration, the data format and the baud rate. More...
 
bool setConfigMode ()
 Sets the device in config mode. More...
 
bool setForceTorqueFilter (const configuration::ForceTorqueFilter &filter)
 Sets a force torque filter to the device. More...
 
bool setForceTorqueOffset (const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
 Sets a force torque offset to the device. More...
 
bool setHardwareReset ()
 Triggers a hardware reset of the sensor. More...
 
bool setInitMode ()
 Triggers a software reset of the sensor bringing it to a known state. More...
 
void setPollingTimeStep (double timeStep)
 Sets the time step of the polling thread in seconds. timeStep The time step in seconds. More...
 
bool setRunMode ()
 Sets the device in run mode. More...
 
bool setSensorCalibration (const calibration::SensorCalibration &sensorCalibration)
 Sets a sensor calibration to the device. More...
 
bool setSensorConfiguration (const configuration::SensorConfiguration &sensorConfiguration)
 Sets a sensor configuration to the device. More...
 
void setState (const uint16_t state)
 Sets the state of the device in the bus (unused). More...
 
void shutdown ()
 Shuts down the device. It automatically shuts-down threads and disconnects from serial-port. More...
 
bool startup ()
 This method starts up communication with the device. More...
 
void updateRead ()
 This method is called by the BusManager. Each device attached to this bus reads its data from the buffer (not used). More...
 
void updateWrite ()
 This method is called by the BusManager. Each device attached to the bus writes its data to the buffer (not used). More...
 
bool waitForState (const uint16_t state)
 Wait for a state to be reached (unused). More...
 
 ~RokubiminiSerialImpl ()=default
 

Private Types

using timespec = struct timespec
 

Private Member Functions

uint16_t calcCrc16X25 (uint8_t *data, int len)
 
bool connect ()
 Connects to the Serial-over-USB port. More...
 
bool connect (const std::string &port)
 Connects to the Serial-over-USB port. More...
 
void connectionWorker ()
 Worker threads for managing sensor connections. More...
 
uint16_t crcCcittUpdate (uint16_t crc, uint8_t data)
 Implementation function of the CRC16 X25 checksum for the input data. More...
 
double diffSec (timespec a, timespec b)
 Calculates the difference (b-a) of two timespecs in seconds. More...
 
std::uint32_t getBaudRateDefinition (const uint32_t &baudRate)
 Returns the system definition for the given baudRate. More...
 
ConnectionState getConnectionState () const
 Retreive sensor state/status. More...
 
ErrorState getErrorState () const
 Gets the current error status. More...
 
std::string getErrorString () const
 Retrieves detailed error indication. More...
 
bool hasError () const
 Checks the connection has errors. More...
 
bool initSensorCommunication (bool keepConnecting)
 Initializatin-time helper functions. More...
 
bool initSerialPort (const std::string &port)
 Sets up and initializes the serial port for communication. More...
 
bool isConnected () const
 Quick sensor/state testers. More...
 
bool isConnecting () const
 Checks if device is already in the process of connecting. More...
 
bool isInConfigMode () const
 Checks if the ModeState is Config Mode. More...
 
void pollingWorker ()
 Worker threads for polling the sensors. More...
 
bool readDevice (RxFrame &frame)
 Reads a raw measurement frame from the serial-port. More...
 
bool sendCalibrationMatrixEntry (const uint8_t subId, const double entry)
 Sends a calibration matrix entry to device. More...
 
bool startPollingThread ()
 This method starts up the polling thread. More...
 
timespec timespecAdd (timespec a, timespec b)
 Calculates the sum of two timespecs. More...
 
double timespecToSec (timespec t)
 Converts a timespec to seconds. More...
 
bool writeSerial (const std::string &str)
 Writes an Ascii string to the serial device. More...
 

Private Attributes

std::uint32_t baudRate_
 The baud rate of the serial communication. More...
 
boost::atomic< ConnectionStateconnectionState_
 Internal connection state. More...
 
boost::thread connectionThread_
 Connection thread handle. More...
 
boost::atomic< ErrorStateerrorState_
 Internal error state. More...
 
RxFrame frame_
 The internal variable for the receiving frame. This variable represents the raw data received from the sensor. More...
 
unsigned long frameCrcErrorCounter_
 Counter for frames with CRC errors. More...
 
uint8_t frameHeader = 0xAA
 The frame header value. More...
 
unsigned long frameReceivedCounter_
 Received frame counter. More...
 
unsigned long frameSuccessCounter_
 Correct frames counter. More...
 
boost::atomic< bool > frameSync_
 Flag that indicates if the frame is synced. More...
 
unsigned int frameSyncErrorCounter_
 Frame sync errors. More...
 
boost::atomic< bool > isRunning_
 Internal flags/indicators. More...
 
unsigned int maxFrameSyncErrorCounts_
 Maximum acceptable frame sync errors. More...
 
boost::atomic< ModeStatemodeState_
 Mode state of the sensor. More...
 
std::string name_
 Name of the sensor. More...
 
unsigned long pollingSyncErrorCounter_
 Internal statistics and error counters. More...
 
boost::thread pollingThread_
 Polling thread handle. More...
 
double pollingThreadTimeStep_
 If setup, the sensor polling thread will poll at this rate. More...
 
std::string port_
 The serial port to connect to. More...
 
std::recursive_mutex readingMutex_
 Mutex prohibiting simultaneous access the internal Reading variable. More...
 
bool runInThreadedMode_
 Flag to indicate whether the driver should setup worker threads at startup. More...
 
Reading serialImplReading_
 The internal reading variable. It's used for providing to client code the sensor readings, through the getReading () function. More...
 
std::recursive_mutex serialMutex_
 Mutex prohibiting simultaneous access to Serial device. More...
 
double timeStampSecs_
 Sample time-stamp. More...
 
boost::atomic< int > usbFileDescriptor_
 The USB file descriptor. More...
 
std::ifstream usbStreamIn_
 Input stream for the USB file descriptor. More...
 
std::ofstream usbStreamOut_
 Output stream for the USB file descriptor. More...
 
bool useDeviceTimeStamps_
 Flag to indicate whether time-stamps should be generated using sensor or system time. More...
 

Static Private Attributes

static const uint64_t NSEC_PER_SEC = 1000000000
 

Detailed Description

The Rokubimini Serial Implementation class.

It's the implementation in the BRIDGE pattern used. It provides the implementation to be called by the interface (RokubiminiSerial) in order to communicate with the Serial Device.

Definition at line 113 of file RokubiminiSerialImpl.hpp.

Member Typedef Documentation

Definition at line 565 of file RokubiminiSerialImpl.hpp.

Constructor & Destructor Documentation

rokubimini::serial::RokubiminiSerialImpl::RokubiminiSerialImpl ( )
delete

Default constructor is deleted.

rokubimini::serial::RokubiminiSerialImpl::RokubiminiSerialImpl ( const std::string &  name,
const std::string &  port,
const std::uint32_t &  baudRate 
)

Custom constructor for the RokubiminiSerialImpl class.

Parameters
nameThe name of the device.
portThe port to connect to.
baudRateThe baud rate of the serial communication.

Definition at line 33 of file RokubiminiSerialImpl.cpp.

rokubimini::serial::RokubiminiSerialImpl::~RokubiminiSerialImpl ( )
default

Member Function Documentation

uint16_t rokubimini::serial::RokubiminiSerialImpl::calcCrc16X25 ( uint8_t *  data,
int  len 
)
inlineprivate

Definition at line 518 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::connect ( )
private

Connects to the Serial-over-USB port.

Returns
True if connection was successful.

Definition at line 138 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::connect ( const std::string &  port)
private

Connects to the Serial-over-USB port.

Parameters
portThe port to connect to.
Returns
True if connection was successful.

Definition at line 178 of file RokubiminiSerialImpl.cpp.

void rokubimini::serial::RokubiminiSerialImpl::connectionWorker ( )
private

Worker threads for managing sensor connections.

Definition at line 536 of file RokubiminiSerialImpl.cpp.

uint16_t rokubimini::serial::RokubiminiSerialImpl::crcCcittUpdate ( uint16_t  crc,
uint8_t  data 
)
private

Implementation function of the CRC16 X25 checksum for the input data.

Parameters
dataThe input data.
crcThe current checksum.
Returns
The new checksum calculated.

Definition at line 526 of file RokubiminiSerialImpl.cpp.

double rokubimini::serial::RokubiminiSerialImpl::diffSec ( timespec  a,
timespec  b 
)
inlineprivate

Calculates the difference (b-a) of two timespecs in seconds.

Parameters
aThe first timespec.
bThe second timespec.
Returns
The difference in seconds.

Definition at line 577 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::firmwareUpdate ( const std::string &  filePath)

Updates the firmware of the device.

Parameters
filePathThe path to find the firmware file
Returns
True if the flashing of firware was successful.

Definition at line 1025 of file RokubiminiSerialImpl.cpp.

uint32_t rokubimini::serial::RokubiminiSerialImpl::getBaudRateDefinition ( const uint32_t &  baudRate)
private

Returns the system definition for the given baudRate.

Parameters
baudRateThe baudRate to find the definition for.
Returns
The system definition.

Definition at line 371 of file RokubiminiSerialImpl.cpp.

ConnectionState rokubimini::serial::RokubiminiSerialImpl::getConnectionState ( ) const
private

Retreive sensor state/status.

Gets the current connection status.

Returns
The current connection status.

Definition at line 310 of file RokubiminiSerialImpl.cpp.

ErrorState rokubimini::serial::RokubiminiSerialImpl::getErrorState ( ) const
private

Gets the current error status.

Returns
The current error status.

Definition at line 315 of file RokubiminiSerialImpl.cpp.

std::string rokubimini::serial::RokubiminiSerialImpl::getErrorString ( ) const
private

Retrieves detailed error indication.

Returns
The error string.

Definition at line 320 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::getForceTorqueSamplingRate ( int &  samplingRate)
inline

Gets the force torque sampling rate of the device.

Parameters
samplingRateThe force torque sampling rate to be fetched.
Returns
True if the force torque sampling rate was successfully fetched.

Definition at line 269 of file RokubiminiSerialImpl.hpp.

std::string rokubimini::serial::RokubiminiSerialImpl::getName ( ) const
inline

Accessor for device name.

Returns
The name of the device.

Definition at line 234 of file RokubiminiSerialImpl.hpp.

void rokubimini::serial::RokubiminiSerialImpl::getReading ( rokubimini::Reading reading)

Gets the internal reading variable.

Parameters
readingThe variable to store the reading.

Definition at line 638 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::getSerialNumber ( unsigned int &  serialNumber)
inline

Accessor for device serial number.

Parameters
serialNumberThe serial number to get.
Returns
True if the serial number could be successfully fetched.

Definition at line 252 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::hasError ( ) const
private

Checks the connection has errors.

Returns
True if the connection has errors.

Definition at line 300 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::hasFrameSync ( )
inline

Returns if there is frame synchronization with the device.

Returns
True if there is.

Definition at line 520 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::init ( )

This method initializes internal variables and the device for communication. It connects to the serial-port.

Returns
True if the initialization was successful.

Definition at line 62 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::initSensorCommunication ( bool  keepConnecting)
private

Initializatin-time helper functions.

Initializes communication with the sensor.

Parameters
keepConnectingSet if there will be multiple attempts or only one.
Returns
True if initialization of the communication was successful.

Definition at line 346 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::initSerialPort ( const std::string &  port)
private

Sets up and initializes the serial port for communication.

Parameters
portThe port to initialize.
Returns
True if the port was initialized successfully.

Definition at line 440 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::isConnected ( ) const
private

Quick sensor/state testers.

Checks if the device is connected.

Returns
True if the device is connected.

Definition at line 290 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::isConnecting ( ) const
private

Checks if device is already in the process of connecting.

Returns
True if device is in the process of connecting.

Definition at line 295 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::isInConfigMode ( ) const
private

Checks if the ModeState is Config Mode.

Returns
True if the ModeState is Config Mode.

Definition at line 305 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::isRunning ( )
inline

Returns if the serial driver is running.

Returns
True if the serial driver is running.

Definition at line 498 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::loadConfig ( )

Loads the configuration of the device.

Returns
True if the operation was successful.

Definition at line 921 of file RokubiminiSerialImpl.cpp.

void rokubimini::serial::RokubiminiSerialImpl::pollingWorker ( )
private

Worker threads for polling the sensors.

Definition at line 541 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::printUserConfig ( )

Prints all the user configurable parameters.

Returns
True if the operation was successful.

Definition at line 939 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::readDevice ( RxFrame frame)
private

Reads a raw measurement frame from the serial-port.

Parameters
frameThe raw measurement frame to read.
Returns
True if the reading was successful.

Definition at line 184 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::saveConfigParameter ( )

Saves the current configuration to the device.

Returns
True if the configuration was successfully saved in the device.

Definition at line 903 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::sendCalibrationMatrixEntry ( const uint8_t  subId,
const double  entry 
)
inlineprivate

Sends a calibration matrix entry to device.

Parameters
subIdThe sub-index of the SDO to write to.
entryThe entry on the matrix.
Returns
True if the operation was successful.

Definition at line 560 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setAccelerationFilter ( const unsigned int  filter)
inline

Sets an acceleration filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the acceleration torque filter was successfully set.

Definition at line 299 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setAccelerationRange ( const unsigned int  range)
inline

Sets an acceleration range to the device.

Parameters
rangeThe range to be set.
Returns
True if the acceleration range was successfully set.

Definition at line 331 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setAngularRateFilter ( const unsigned int  filter)
inline

Sets an angular rate filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the angular rate filter was successfully set.

Definition at line 315 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setAngularRateRange ( const unsigned int  range)
inline

Sets an angular rate range to the device.

Parameters
rangeThe range to be set.
Returns
True if the angular rate range was successfully set.

Definition at line 347 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setCommunicationSetup ( const configuration::SensorConfiguration sensorConfiguration,
const uint8_t &  dataFormat,
const uint32_t &  baudRate 
)

Sets communication setup for the device. This includes setting the temperature compensation, the matrix calibration, the data format and the baud rate.

Parameters
sensorConfigurationThe sensor configuration to be set.
dataFormatThe data format (binary = 0, CSV = 1).
baudRateThe desired baud rate (see user manual).
Returns
True if the operation was successful.

Definition at line 864 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setConfigMode ( )

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 665 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setForceTorqueFilter ( const configuration::ForceTorqueFilter filter)

Sets a force torque filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the force torque filter was successfully set.

Definition at line 774 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setForceTorqueOffset ( const Eigen::Matrix< double, 6, 1 > &  forceTorqueOffset)

Sets a force torque offset to the device.

Parameters
forceTorqueOffsetThe offset to be set.
Returns
True if the offset was successfully set.

Definition at line 800 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setHardwareReset ( )

Triggers a hardware reset of the sensor.

Returns
True if the operation was successful.

Definition at line 723 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setInitMode ( )

Triggers a software reset of the sensor bringing it to a known state.

Returns
True if the operation was successful.

Definition at line 738 of file RokubiminiSerialImpl.cpp.

void rokubimini::serial::RokubiminiSerialImpl::setPollingTimeStep ( double  timeStep)
inline

Sets the time step of the polling thread in seconds. timeStep The time step in seconds.

Definition at line 509 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::setRunMode ( )

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 701 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setSensorCalibration ( const calibration::SensorCalibration sensorCalibration)

Sets a sensor calibration to the device.

Parameters
sensorCalibrationThe calibration to be set.
Returns
True if the calibration was successfully set.

Definition at line 821 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::setSensorConfiguration ( const configuration::SensorConfiguration sensorConfiguration)

Sets a sensor configuration to the device.

Parameters
sensorConfigurationThe configuration to be set.
Returns
True if the configuration was successfully set.

Definition at line 852 of file RokubiminiSerialImpl.cpp.

void rokubimini::serial::RokubiminiSerialImpl::setState ( const uint16_t  state)
inline

Sets the state of the device in the bus (unused).

Parameters
stateDesired state.
Returns
True if the angular rate filter was successfully set.

Definition at line 208 of file RokubiminiSerialImpl.hpp.

void rokubimini::serial::RokubiminiSerialImpl::shutdown ( )

Shuts down the device. It automatically shuts-down threads and disconnects from serial-port.

Definition at line 184 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::startPollingThread ( )
private

This method starts up the polling thread.

Returns
True if the operation was successful.

Definition at line 86 of file RokubiminiSerialImpl.cpp.

bool rokubimini::serial::RokubiminiSerialImpl::startup ( )

This method starts up communication with the device.

Returns
True if the startup was successful.

Definition at line 98 of file RokubiminiSerialImpl.cpp.

timespec rokubimini::serial::RokubiminiSerialImpl::timespecAdd ( timespec  a,
timespec  b 
)
inlineprivate

Calculates the sum of two timespecs.

Parameters
aThe first timespec.
bThe second timespec.
Returns
The timespec after adding the two input timespecs.

Definition at line 606 of file RokubiminiSerialImpl.hpp.

double rokubimini::serial::RokubiminiSerialImpl::timespecToSec ( timespec  t)
inlineprivate

Converts a timespec to seconds.

Parameters
tThe timespec.
Returns
The seconds.

Definition at line 591 of file RokubiminiSerialImpl.hpp.

void rokubimini::serial::RokubiminiSerialImpl::updateRead ( )
inline

This method is called by the BusManager. Each device attached to this bus reads its data from the buffer (not used).

Definition at line 173 of file RokubiminiSerialImpl.hpp.

void rokubimini::serial::RokubiminiSerialImpl::updateWrite ( )
inline

This method is called by the BusManager. Each device attached to the bus writes its data to the buffer (not used).

Definition at line 184 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::waitForState ( const uint16_t  state)
inline

Wait for a state to be reached (unused).

Parameters
stateDesired state.
Returns
True if the state has been reached within the timeout.

Definition at line 220 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::writeSerial ( const std::string &  str)
private

Writes an Ascii string to the serial device.

Parameters
strThe string to write.
Returns
True if the operation was successful.

Definition at line 982 of file RokubiminiSerialImpl.cpp.

Member Data Documentation

std::uint32_t rokubimini::serial::RokubiminiSerialImpl::baudRate_
private

The baud rate of the serial communication.

Definition at line 865 of file RokubiminiSerialImpl.hpp.

boost::atomic< ConnectionState > rokubimini::serial::RokubiminiSerialImpl::connectionState_
private

Internal connection state.

Definition at line 1013 of file RokubiminiSerialImpl.hpp.

boost::thread rokubimini::serial::RokubiminiSerialImpl::connectionThread_
private

Connection thread handle.

Definition at line 995 of file RokubiminiSerialImpl.hpp.

boost::atomic< ErrorState > rokubimini::serial::RokubiminiSerialImpl::errorState_
private

Internal error state.

Definition at line 1021 of file RokubiminiSerialImpl.hpp.

RxFrame rokubimini::serial::RokubiminiSerialImpl::frame_
private

The internal variable for the receiving frame. This variable represents the raw data received from the sensor.

Definition at line 945 of file RokubiminiSerialImpl.hpp.

unsigned long rokubimini::serial::RokubiminiSerialImpl::frameCrcErrorCounter_
private

Counter for frames with CRC errors.

Definition at line 1074 of file RokubiminiSerialImpl.hpp.

uint8_t rokubimini::serial::RokubiminiSerialImpl::frameHeader = 0xAA
private

The frame header value.

Definition at line 935 of file RokubiminiSerialImpl.hpp.

unsigned long rokubimini::serial::RokubiminiSerialImpl::frameReceivedCounter_
private

Received frame counter.

Definition at line 1056 of file RokubiminiSerialImpl.hpp.

unsigned long rokubimini::serial::RokubiminiSerialImpl::frameSuccessCounter_
private

Correct frames counter.

Definition at line 1065 of file RokubiminiSerialImpl.hpp.

boost::atomic< bool > rokubimini::serial::RokubiminiSerialImpl::frameSync_
private

Flag that indicates if the frame is synced.

Definition at line 908 of file RokubiminiSerialImpl.hpp.

unsigned int rokubimini::serial::RokubiminiSerialImpl::frameSyncErrorCounter_
private

Frame sync errors.

Definition at line 1082 of file RokubiminiSerialImpl.hpp.

boost::atomic< bool > rokubimini::serial::RokubiminiSerialImpl::isRunning_
private

Internal flags/indicators.

Internal flag to indicate if the threads are running.

Definition at line 1038 of file RokubiminiSerialImpl.hpp.

unsigned int rokubimini::serial::RokubiminiSerialImpl::maxFrameSyncErrorCounts_
private

Maximum acceptable frame sync errors.

Definition at line 1090 of file RokubiminiSerialImpl.hpp.

boost::atomic< ModeState > rokubimini::serial::RokubiminiSerialImpl::modeState_
private

Mode state of the sensor.

Definition at line 1030 of file RokubiminiSerialImpl.hpp.

std::string rokubimini::serial::RokubiminiSerialImpl::name_
private

Name of the sensor.

Definition at line 836 of file RokubiminiSerialImpl.hpp.

const uint64_t rokubimini::serial::RokubiminiSerialImpl::NSEC_PER_SEC = 1000000000
staticprivate

Definition at line 1097 of file RokubiminiSerialImpl.hpp.

unsigned long rokubimini::serial::RokubiminiSerialImpl::pollingSyncErrorCounter_
private

Internal statistics and error counters.

Synchronization error counter.

Definition at line 1048 of file RokubiminiSerialImpl.hpp.

boost::thread rokubimini::serial::RokubiminiSerialImpl::pollingThread_
private

Polling thread handle.

Definition at line 1004 of file RokubiminiSerialImpl.hpp.

double rokubimini::serial::RokubiminiSerialImpl::pollingThreadTimeStep_
private

If setup, the sensor polling thread will poll at this rate.

Definition at line 976 of file RokubiminiSerialImpl.hpp.

std::string rokubimini::serial::RokubiminiSerialImpl::port_
private

The serial port to connect to.

Definition at line 856 of file RokubiminiSerialImpl.hpp.

std::recursive_mutex rokubimini::serial::RokubiminiSerialImpl::readingMutex_
mutableprivate

Mutex prohibiting simultaneous access the internal Reading variable.

Definition at line 874 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::runInThreadedMode_
private

Flag to indicate whether the driver should setup worker threads at startup.

Definition at line 966 of file RokubiminiSerialImpl.hpp.

Reading rokubimini::serial::RokubiminiSerialImpl::serialImplReading_
private

The internal reading variable. It's used for providing to client code the sensor readings, through the getReading () function.

Definition at line 847 of file RokubiminiSerialImpl.hpp.

std::recursive_mutex rokubimini::serial::RokubiminiSerialImpl::serialMutex_
mutableprivate

Mutex prohibiting simultaneous access to Serial device.

Definition at line 883 of file RokubiminiSerialImpl.hpp.

double rokubimini::serial::RokubiminiSerialImpl::timeStampSecs_
private

Sample time-stamp.

Definition at line 957 of file RokubiminiSerialImpl.hpp.

boost::atomic< int > rokubimini::serial::RokubiminiSerialImpl::usbFileDescriptor_
private

The USB file descriptor.

Definition at line 899 of file RokubiminiSerialImpl.hpp.

std::ifstream rokubimini::serial::RokubiminiSerialImpl::usbStreamIn_
private

Input stream for the USB file descriptor.

Definition at line 917 of file RokubiminiSerialImpl.hpp.

std::ofstream rokubimini::serial::RokubiminiSerialImpl::usbStreamOut_
private

Output stream for the USB file descriptor.

Definition at line 926 of file RokubiminiSerialImpl.hpp.

bool rokubimini::serial::RokubiminiSerialImpl::useDeviceTimeStamps_
private

Flag to indicate whether time-stamps should be generated using sensor or system time.

Definition at line 986 of file RokubiminiSerialImpl.hpp.


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


rokubimini_serial
Author(s):
autogenerated on Wed Mar 3 2021 03:09:18