The Rokubimini Serial Implementation class. More...
#include <RokubiminiSerialImpl.hpp>
Public Member Functions | |
void | closeSerialPort () |
Closes the serial port. More... | |
void | createDataFlagsDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Creates the Data Flags Diagnostics status. More... | |
bool | firmwareUpdate (const std::string &filePath) |
Updates the firmware of the device. More... | |
std::string | getConnectionStateString () const |
std::vector< std::string > | getErrorStrings () const |
Retrieves detailed error indication. More... | |
bool | getForceTorqueSamplingRate (int &samplingRate) |
Gets the force torque sampling rate of the device. More... | |
void | getFrameDataStatus (DataStatus &status) |
Gets the latest frame's Data Status. More... | |
std::string | getModeStateString () const |
std::string | getName () const |
Accessor for device name. More... | |
std::string | getProductName () const |
Gets the product name of the device. More... | |
void | getReading (rokubimini::Reading &reading) |
Gets the internal reading variable. More... | |
bool | getSerialNumber (unsigned int &serialNumber) |
Accessor for device serial number. More... | |
bool | hasError () const |
Checks the connection has errors. 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 | parseCommunicationMsgs (const double &timeout=1.0) |
Parses the Communication Messages of the serial sensor. More... | |
bool | printUserConfig () |
Prints all the user configurable parameters. More... | |
void | resetDataFlags () |
Resets the Data Flags variable currentDataFlagsDiagnostics_ . More... | |
RokubiminiSerialImpl ()=delete | |
Default constructor is deleted. More... | |
RokubiminiSerialImpl (const std::string &name, const std::string &port) | |
bool | runsAsync () |
Returns if the driver runs asynchronously. 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 uint8_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... | |
bool | setRunMode () |
Sets the device in run mode. More... | |
void | setRunsAsync (bool runsAsync) |
Sets the runsAsync_ variable. 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 | 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 | updateConnectionStatus (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Fills the Device Connection Status (ROS diagnostics). More... | |
void | updateDataFlags () |
Updates the Data Flags variable currentDataFlagsDiagnostics_ . 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... | |
~RokubiminiSerialImpl ()=default | |
Private Types | |
using | timespec = struct timespec |
Private Member Functions | |
uint16_t | calcCrc16X25 (uint8_t *data, int len) |
bool | clearReadBuffer () |
Clears the Read Serial buffer by extracting every character available. More... | |
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... | |
ConnectionState | getConnectionState () const |
Gets the current connection status. More... | |
ErrorFlags | getErrorFlags () const |
Gets the current error status. More... | |
void | increaseAndCheckTimeoutCounter () |
Increases the timeout counter and checks if it has passed the maximum available timeouts. More... | |
bool | initSensorCommunication (bool keepOpening) |
Initializes communication with the sensor. More... | |
bool | initSerialPort (const std::string &port) |
Sets up and initializes the serial port for communication. More... | |
bool | isConnected () const |
Checks if the device is connected. 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... | |
bool | openSerialPort (bool keepOpening) |
Opens the serial port. More... | |
bool | parseAcknowledgement (const char &command_code, const double &timeout=2.0) |
Parses the acknowledgement from the serial device. More... | |
bool | parseRegexWaitTimeout (RokubiminiSerialResponseRegex ®, const double &timeout=1.0) |
Parses a regex from the serial sensor input stream. 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 | readSerialNoWait (const uint32_t &numChars, std::string &str) |
Reads a string from the serial device without waiting. The number of characters of the string is not guaranteed to be equal with the number of characters given as parameter. More... | |
bool | readSerialWaitTimeout (const uint32_t &numChars, std::string &str, const double &timeout=1.0) |
Reads a string from the serial device waiting a timeout duration. The number of characters of the string is not guaranteed to be equal with the number of characters given as parameter. More... | |
bool | sendCalibrationMatrixEntry (const uint8_t subId, const double entry) |
Sends a calibration matrix entry to device. More... | |
bool | sendCommand (const std::string &command) |
Sends a command to the serial 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 | |
BaudRateStruct | baudRate_ |
The baud rate of the serial communication, as a termios bit mask. More... | |
boost::atomic< ConnectionState > | connectionState_ |
Internal connection state. More... | |
boost::thread | connectionThread_ |
Connection thread handle. More... | |
std::atomic< DataStatus > | currentDataFlagsDiagnostics_ |
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and is published by the DataFlagsDiagnosticsPublisher. More... | |
bool | dataReady_ |
This flag is on when new data are ready to be published. More... | |
ErrorFlags | errorFlags_ |
Flags to indicate errors in serial communication. 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... | |
DataStatus | frameDataStatus_ |
The current frame's Data Status. More... | |
uint8_t | frameHeader = 0xAA |
The frame header value. More... | |
uint32_t | frameOffset_ |
The frame offset to start reading (in bytes). 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... | |
ros::Time | frameTimestamp_ |
boost::atomic< bool > | isRunning_ |
Internal flags/indicators. More... | |
unsigned int | maxCountOpenSerialPort_ |
Maximum attempts to open serial port. More... | |
unsigned int | maxFrameSyncErrorCounts_ |
Maximum acceptable frame sync errors. More... | |
boost::atomic< ModeState > | modeState_ |
Mode state of the sensor. More... | |
std::string | name_ |
Name of the sensor. More... | |
std::condition_variable | newFrameIsAvailable_ |
The condition variable that is used between the publishing and the polling thread to synchronize on new data. More... | |
RxFrame | placeholder_ |
A placeholder to save unfinished frames. More... | |
unsigned long | pollingSyncErrorCounter_ |
Internal statistics and error counters. More... | |
boost::thread | pollingThread_ |
Polling thread handle. More... | |
std::string | port_ |
The serial port to connect to. More... | |
std::string | productName_ |
The product name of the device. More... | |
std::mutex | readingMutex_ |
Mutex prohibiting simultaneous access the internal Reading variable. More... | |
double | readTimeout_ |
The timeout to read from device (in seconds). More... | |
bool | runInThreadedMode_ |
Flag to indicate whether the driver should setup worker threads at startup. More... | |
std::atomic< bool > | runsAsync_ |
The flag that represents whether the driver runs asynchronously or not. 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... | |
uint32_t | serialNumber_ |
The serial number of the device. More... | |
unsigned int | timeoutCounter_ |
Timeout counter. 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... | |
Static Private Attributes | |
const static uint8_t | DEFAULT_BAUD_RATE_OPTION = 3 |
constexpr static double | FTDI_DRIVER_LATENCY = 0.001 |
const static uint8_t | MAX_BAUD_RATE_OPTION = 4 |
constexpr static double | MAXIMUM_ACCEPTABLE_TIMEOUT = 1.77 |
const static uint64_t | NSEC_PER_SEC = 1000000000 |
constexpr static double | TIMEOUT_MARGIN = 0.15 |
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 131 of file RokubiminiSerialImpl.hpp.
|
private |
Definition at line 757 of file RokubiminiSerialImpl.hpp.
|
delete |
Default constructor is deleted.
rokubimini::serial::RokubiminiSerialImpl::RokubiminiSerialImpl | ( | const std::string & | name, |
const std::string & | port | ||
) |
Definition at line 33 of file RokubiminiSerialImpl.cpp.
|
default |
|
inlineprivate |
Definition at line 767 of file RokubiminiSerialImpl.cpp.
|
private |
Clears the Read Serial buffer by extracting every character available.
Definition at line 1238 of file RokubiminiSerialImpl.cpp.
void rokubimini::serial::RokubiminiSerialImpl::closeSerialPort | ( | ) |
Closes the serial port.
Definition at line 202 of file RokubiminiSerialImpl.hpp.
|
private |
Connects to the Serial-over-USB port.
Definition at line 171 of file RokubiminiSerialImpl.cpp.
|
private |
Connects to the Serial-over-USB port.
port | The port to connect to. |
Definition at line 212 of file RokubiminiSerialImpl.cpp.
|
private |
Worker threads for managing sensor connections.
Definition at line 785 of file RokubiminiSerialImpl.cpp.
|
private |
Implementation function of the CRC16 X25 checksum for the input data.
data | The input data. |
crc | The current checksum. |
Definition at line 775 of file RokubiminiSerialImpl.cpp.
void rokubimini::serial::RokubiminiSerialImpl::createDataFlagsDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Creates the Data Flags Diagnostics status.
stat | The status to be filled with the new diagnostics. |
Definition at line 1292 of file RokubiminiSerialImpl.cpp.
Calculates the difference (b-a) of two timespecs in seconds.
a | The first timespec. |
b | The second timespec. |
Definition at line 769 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::firmwareUpdate | ( | const std::string & | filePath | ) |
Updates the firmware of the device.
filePath | The path to find the firmware file |
Definition at line 1396 of file RokubiminiSerialImpl.cpp.
|
private |
Gets the current connection status.
Definition at line 406 of file RokubiminiSerialImpl.cpp.
|
inline |
Definition at line 254 of file RokubiminiSerialImpl.hpp.
|
private |
Gets the current error status.
Definition at line 411 of file RokubiminiSerialImpl.cpp.
std::vector< std::string > rokubimini::serial::RokubiminiSerialImpl::getErrorStrings | ( | ) | const |
Retrieves detailed error indication.
Definition at line 416 of file RokubiminiSerialImpl.cpp.
|
inline |
Gets the force torque sampling rate of the device.
samplingRate | The force torque sampling rate to be fetched. |
Definition at line 298 of file RokubiminiSerialImpl.hpp.
void rokubimini::serial::RokubiminiSerialImpl::getFrameDataStatus | ( | DataStatus & | status | ) |
Gets the latest frame's Data Status.
status | The status to be filled with the latest Data Status. |
Definition at line 1325 of file RokubiminiSerialImpl.cpp.
|
inline |
Definition at line 239 of file RokubiminiSerialImpl.hpp.
|
inline |
Accessor for device name.
Definition at line 234 of file RokubiminiSerialImpl.hpp.
|
inline |
Gets the product name of the device.
Definition at line 558 of file RokubiminiSerialImpl.hpp.
void rokubimini::serial::RokubiminiSerialImpl::getReading | ( | rokubimini::Reading & | reading | ) |
Gets the internal reading variable.
reading | The variable to store the reading. |
Definition at line 898 of file RokubiminiSerialImpl.cpp.
|
inline |
Accessor for device serial number.
serialNumber | The serial number to get. |
Definition at line 280 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::hasError | ( | ) | const |
Checks the connection has errors.
Definition at line 391 of file RokubiminiSerialImpl.cpp.
|
inline |
Returns if there is frame synchronization with the device.
Definition at line 537 of file RokubiminiSerialImpl.hpp.
|
private |
Increases the timeout counter and checks if it has passed the maximum available timeouts.
Definition at line 218 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::init | ( | ) |
This method initializes internal variables and the device for communication. It connects to the serial-port.
Definition at line 65 of file RokubiminiSerialImpl.cpp.
|
private |
Initializes communication with the sensor.
keepOpening | Set if there will be multiple attempts or only one. |
Step 1. Open port in every possible baud rate and send hardware reset.
Step 2. Open port with default baud rate and parse communication setup.
Step 3. Apply the following logic:
Definition at line 465 of file RokubiminiSerialImpl.cpp.
|
private |
Sets up and initializes the serial port for communication.
port | The port to initialize. |
Definition at line 699 of file RokubiminiSerialImpl.cpp.
|
private |
Checks if the device is connected.
Definition at line 381 of file RokubiminiSerialImpl.cpp.
|
private |
Checks if device is already in the process of connecting.
Definition at line 386 of file RokubiminiSerialImpl.cpp.
|
private |
Checks if the ModeState is Config Mode.
Definition at line 401 of file RokubiminiSerialImpl.cpp.
|
inline |
Returns if the serial driver is running.
Definition at line 526 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::loadConfig | ( | ) |
Loads the configuration of the device.
Definition at line 1167 of file RokubiminiSerialImpl.cpp.
|
private |
Opens the serial port.
keepOpening | Set if there will be multiple attempts or only one. |
Definition at line 445 of file RokubiminiSerialImpl.cpp.
|
private |
Parses the acknowledgement from the serial device.
command_code | The command code to parse the ACK for. |
timeout | The timeout in seconds to wait before parsing the acknowledgement. By default this is set to 2 seconds. |
Definition at line 1331 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::parseCommunicationMsgs | ( | const double & | timeout = 1.0 | ) |
Parses the Communication Messages of the serial sensor.
timeout | The timeout in seconds to wait. By default this is set to 1 seconds. |
Definition at line 669 of file RokubiminiSerialImpl.cpp.
|
private |
Parses a regex from the serial sensor input stream.
regex | The regex to be parsed. |
timeout | The timeout in seconds to wait before parsing the regex. By default this is set to 1 seconds. |
Definition at line 614 of file RokubiminiSerialImpl.cpp.
|
private |
Worker threads for polling the sensors.
Definition at line 790 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::printUserConfig | ( | ) |
Prints all the user configurable parameters.
Definition at line 1186 of file RokubiminiSerialImpl.cpp.
|
private |
Reads a raw measurement frame from the serial-port.
frame | The raw measurement frame to read. |
Definition at line 224 of file RokubiminiSerialImpl.cpp.
|
private |
Reads a string from the serial device without waiting. The number of characters of the string is not guaranteed to be equal with the number of characters given as parameter.
numChars | The number of chars to read. |
str | The string to read. |
Definition at line 637 of file RokubiminiSerialImpl.cpp.
|
private |
Reads a string from the serial device waiting a timeout duration. The number of characters of the string is not guaranteed to be equal with the number of characters given as parameter.
numChars | The number of chars to read. |
str | The string to read. |
timeout | The timeout in seconds to wait. By default this is set to 1 seconds. |
Definition at line 647 of file RokubiminiSerialImpl.cpp.
void rokubimini::serial::RokubiminiSerialImpl::resetDataFlags | ( | ) |
Resets the Data Flags variable currentDataFlagsDiagnostics_
.
Definition at line 1287 of file RokubiminiSerialImpl.cpp.
|
inline |
Returns if the driver runs asynchronously.
Definition at line 569 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::saveConfigParameter | ( | ) |
Saves the current configuration to the device.
Definition at line 1148 of file RokubiminiSerialImpl.cpp.
|
inlineprivate |
Sends a calibration matrix entry to device.
subId | The sub-index of the SDO to write to. |
entry | The entry on the matrix. |
Definition at line 742 of file RokubiminiSerialImpl.hpp.
|
private |
Sends a command to the serial device.
command | The command to send. |
Definition at line 1229 of file RokubiminiSerialImpl.cpp.
|
inline |
Sets an acceleration filter to the device.
filter | The filter to be set. |
Definition at line 328 of file RokubiminiSerialImpl.hpp.
|
inline |
Sets an acceleration range to the device.
range | The range to be set. |
Definition at line 360 of file RokubiminiSerialImpl.hpp.
|
inline |
Sets an angular rate filter to the device.
filter | The filter to be set. |
Definition at line 344 of file RokubiminiSerialImpl.hpp.
|
inline |
Sets an angular rate range to the device.
range | The range to be set. |
Definition at line 376 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::setCommunicationSetup | ( | const configuration::SensorConfiguration & | sensorConfiguration, |
const uint8_t & | dataFormat, | ||
const uint8_t & | baudRate | ||
) |
Sets communication setup for the device. This includes setting the temperature compensation, the matrix calibration, the data format and the baud rate.
sensorConfiguration | The sensor configuration to be set. |
dataFormat | The data format (binary = 0, CSV = 1). |
baudRate | The desired baud rate (see user manual). |
Definition at line 1129 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setConfigMode | ( | ) |
Sets the device in config mode.
Definition at line 930 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setForceTorqueFilter | ( | const configuration::ForceTorqueFilter & | filter | ) |
Sets a force torque filter to the device.
filter | The filter to be set. |
Definition at line 1039 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setForceTorqueOffset | ( | const Eigen::Matrix< double, 6, 1 > & | forceTorqueOffset | ) |
Sets a force torque offset to the device.
forceTorqueOffset | The offset to be set. |
Definition at line 1065 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setHardwareReset | ( | ) |
Triggers a hardware reset of the sensor.
Definition at line 989 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setInitMode | ( | ) |
Triggers a software reset of the sensor bringing it to a known state.
Definition at line 1004 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setRunMode | ( | ) |
Sets the device in run mode.
Definition at line 967 of file RokubiminiSerialImpl.cpp.
|
inline |
Sets the runsAsync_ variable.
runsAsync | The variable to set. |
Definition at line 580 of file RokubiminiSerialImpl.hpp.
bool rokubimini::serial::RokubiminiSerialImpl::setSensorCalibration | ( | const calibration::SensorCalibration & | sensorCalibration | ) |
Sets a sensor calibration to the device.
sensorCalibration | The calibration to be set. |
Definition at line 1086 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::setSensorConfiguration | ( | const configuration::SensorConfiguration & | sensorConfiguration | ) |
Sets a sensor configuration to the device.
sensorConfiguration | The configuration to be set. |
Definition at line 1117 of file RokubiminiSerialImpl.cpp.
void rokubimini::serial::RokubiminiSerialImpl::shutdown | ( | ) |
Shuts down the device. It automatically shuts-down threads and disconnects from serial-port.
Definition at line 138 of file RokubiminiSerialImpl.cpp.
|
private |
This method starts up the polling thread.
Definition at line 97 of file RokubiminiSerialImpl.cpp.
bool rokubimini::serial::RokubiminiSerialImpl::startup | ( | ) |
This method starts up communication with the device.
Definition at line 109 of file RokubiminiSerialImpl.cpp.
|
inlineprivate |
Calculates the sum of two timespecs.
a | The first timespec. |
b | The second timespec. |
Definition at line 798 of file RokubiminiSerialImpl.hpp.
|
inlineprivate |
Converts a timespec to seconds.
t | The timespec. |
Definition at line 783 of file RokubiminiSerialImpl.hpp.
void rokubimini::serial::RokubiminiSerialImpl::updateConnectionStatus | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Fills the Device Connection Status (ROS diagnostics).
stat | The status to be filled with the new diagnostics. |
Definition at line 1249 of file RokubiminiSerialImpl.cpp.
void rokubimini::serial::RokubiminiSerialImpl::updateDataFlags | ( | ) |
Updates the Data Flags variable currentDataFlagsDiagnostics_
.
Definition at line 1279 of file RokubiminiSerialImpl.cpp.
|
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 191 of file RokubiminiSerialImpl.hpp.
|
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 202 of file RokubiminiSerialImpl.hpp.
|
private |
Writes an Ascii string to the serial device.
str | The string to write. |
Definition at line 1353 of file RokubiminiSerialImpl.cpp.
|
private |
The baud rate of the serial communication, as a termios bit mask.
Definition at line 1031 of file RokubiminiSerialImpl.hpp.
|
private |
Internal connection state.
Definition at line 1162 of file RokubiminiSerialImpl.hpp.
|
private |
Connection thread handle.
Definition at line 1144 of file RokubiminiSerialImpl.hpp.
|
private |
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and is published by the DataFlagsDiagnosticsPublisher.
Definition at line 1369 of file RokubiminiSerialImpl.hpp.
|
private |
This flag is on when new data are ready to be published.
Definition at line 1343 of file RokubiminiSerialImpl.hpp.
|
staticprivate |
Definition at line 1258 of file RokubiminiSerialImpl.hpp.
|
private |
Flags to indicate errors in serial communication.
Definition at line 1170 of file RokubiminiSerialImpl.hpp.
|
private |
The internal variable for the receiving frame. This variable represents the raw data received from the sensor.
Definition at line 1122 of file RokubiminiSerialImpl.hpp.
|
private |
Counter for frames with CRC errors.
Definition at line 1221 of file RokubiminiSerialImpl.hpp.
|
private |
The current frame's Data Status.
Definition at line 1359 of file RokubiminiSerialImpl.hpp.
|
private |
The frame header value.
Definition at line 1112 of file RokubiminiSerialImpl.hpp.
|
private |
The frame offset to start reading (in bytes).
Definition at line 1273 of file RokubiminiSerialImpl.hpp.
|
private |
Received frame counter.
Definition at line 1203 of file RokubiminiSerialImpl.hpp.
|
private |
Correct frames counter.
Definition at line 1212 of file RokubiminiSerialImpl.hpp.
|
private |
Flag that indicates if the frame is synced.
Definition at line 1085 of file RokubiminiSerialImpl.hpp.
|
private |
Frame sync errors.
Definition at line 1229 of file RokubiminiSerialImpl.hpp.
|
private |
Definition at line 1370 of file RokubiminiSerialImpl.hpp.
|
staticconstexprprivate |
Definition at line 1293 of file RokubiminiSerialImpl.hpp.
|
private |
Internal flags/indicators.
Internal flag to indicate if the threads are running.
Definition at line 1186 of file RokubiminiSerialImpl.hpp.
|
staticprivate |
Definition at line 1265 of file RokubiminiSerialImpl.hpp.
|
private |
Maximum attempts to open serial port.
Definition at line 1244 of file RokubiminiSerialImpl.hpp.
|
private |
Maximum acceptable frame sync errors.
Definition at line 1237 of file RokubiminiSerialImpl.hpp.
|
staticconstexprprivate |
Definition at line 1310 of file RokubiminiSerialImpl.hpp.
|
private |
Mode state of the sensor.
Definition at line 1178 of file RokubiminiSerialImpl.hpp.
|
private |
Name of the sensor.
Definition at line 1002 of file RokubiminiSerialImpl.hpp.
|
private |
The condition variable that is used between the publishing and the polling thread to synchronize on new data.
Definition at line 1335 of file RokubiminiSerialImpl.hpp.
|
staticprivate |
Definition at line 1251 of file RokubiminiSerialImpl.hpp.
|
private |
A placeholder to save unfinished frames.
Definition at line 1281 of file RokubiminiSerialImpl.hpp.
|
private |
Internal statistics and error counters.
Synchronization error counter.
Definition at line 1195 of file RokubiminiSerialImpl.hpp.
|
private |
Polling thread handle.
Definition at line 1153 of file RokubiminiSerialImpl.hpp.
|
private |
The serial port to connect to.
Definition at line 1022 of file RokubiminiSerialImpl.hpp.
|
private |
The product name of the device.
Definition at line 1040 of file RokubiminiSerialImpl.hpp.
|
mutableprivate |
Mutex prohibiting simultaneous access the internal Reading variable.
Definition at line 1058 of file RokubiminiSerialImpl.hpp.
|
private |
The timeout to read from device (in seconds).
Definition at line 1318 of file RokubiminiSerialImpl.hpp.
|
private |
Flag to indicate whether the driver should setup worker threads at startup.
Definition at line 1135 of file RokubiminiSerialImpl.hpp.
|
private |
The flag that represents whether the driver runs asynchronously or not.
Definition at line 1351 of file RokubiminiSerialImpl.hpp.
|
private |
The internal reading variable. It's used for providing to client code the sensor readings, through the getReading () function.
Definition at line 1013 of file RokubiminiSerialImpl.hpp.
|
mutableprivate |
Mutex prohibiting simultaneous access to Serial device.
Definition at line 1067 of file RokubiminiSerialImpl.hpp.
|
private |
The serial number of the device.
Definition at line 1049 of file RokubiminiSerialImpl.hpp.
|
staticconstexprprivate |
Definition at line 1301 of file RokubiminiSerialImpl.hpp.
|
private |
Timeout counter.
Definition at line 1326 of file RokubiminiSerialImpl.hpp.
|
private |
The USB file descriptor.
Definition at line 1076 of file RokubiminiSerialImpl.hpp.
|
private |
Input stream for the USB file descriptor.
Definition at line 1094 of file RokubiminiSerialImpl.hpp.
|
private |
Output stream for the USB file descriptor.
Definition at line 1103 of file RokubiminiSerialImpl.hpp.