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

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 &reg, 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< ConnectionStateconnectionState_
 Internal connection state. More...
 
boost::thread connectionThread_
 Connection thread handle. More...
 
std::atomic< DataStatuscurrentDataFlagsDiagnostics_
 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< ModeStatemodeState_
 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
 

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 131 of file RokubiminiSerialImpl.hpp.

Member Typedef Documentation

◆ timespec

Definition at line 757 of file RokubiminiSerialImpl.hpp.

Constructor & Destructor Documentation

◆ RokubiminiSerialImpl() [1/2]

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

Default constructor is deleted.

◆ RokubiminiSerialImpl() [2/2]

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

Definition at line 33 of file RokubiminiSerialImpl.cpp.

◆ ~RokubiminiSerialImpl()

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

Member Function Documentation

◆ calcCrc16X25()

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

Definition at line 767 of file RokubiminiSerialImpl.cpp.

◆ clearReadBuffer()

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

Clears the Read Serial buffer by extracting every character available.

Returns
True if the acknowledgement was received successfully.

Definition at line 1238 of file RokubiminiSerialImpl.cpp.

◆ closeSerialPort()

void rokubimini::serial::RokubiminiSerialImpl::closeSerialPort ( )

Closes the serial port.

Definition at line 202 of file RokubiminiSerialImpl.hpp.

◆ connect() [1/2]

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

Connects to the Serial-over-USB port.

Returns
True if connection was successful.

Definition at line 171 of file RokubiminiSerialImpl.cpp.

◆ connect() [2/2]

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 212 of file RokubiminiSerialImpl.cpp.

◆ connectionWorker()

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

Worker threads for managing sensor connections.

Definition at line 785 of file RokubiminiSerialImpl.cpp.

◆ crcCcittUpdate()

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 775 of file RokubiminiSerialImpl.cpp.

◆ createDataFlagsDiagnostics()

void rokubimini::serial::RokubiminiSerialImpl::createDataFlagsDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)

Creates the Data Flags Diagnostics status.

Parameters
statThe status to be filled with the new diagnostics.

Definition at line 1292 of file RokubiminiSerialImpl.cpp.

◆ diffSec()

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 769 of file RokubiminiSerialImpl.hpp.

◆ firmwareUpdate()

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 1396 of file RokubiminiSerialImpl.cpp.

◆ getConnectionState()

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

Gets the current connection status.

Returns
The current connection status.

Definition at line 406 of file RokubiminiSerialImpl.cpp.

◆ getConnectionStateString()

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

Definition at line 254 of file RokubiminiSerialImpl.hpp.

◆ getErrorFlags()

ErrorFlags rokubimini::serial::RokubiminiSerialImpl::getErrorFlags ( ) const
private

Gets the current error status.

Returns
The current error status.

Definition at line 411 of file RokubiminiSerialImpl.cpp.

◆ getErrorStrings()

std::vector< std::string > rokubimini::serial::RokubiminiSerialImpl::getErrorStrings ( ) const

Retrieves detailed error indication.

Returns
The error string.

Definition at line 416 of file RokubiminiSerialImpl.cpp.

◆ getForceTorqueSamplingRate()

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 298 of file RokubiminiSerialImpl.hpp.

◆ getFrameDataStatus()

void rokubimini::serial::RokubiminiSerialImpl::getFrameDataStatus ( DataStatus status)

Gets the latest frame's Data Status.

Parameters
statusThe status to be filled with the latest Data Status.

Definition at line 1325 of file RokubiminiSerialImpl.cpp.

◆ getModeStateString()

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

Definition at line 239 of file RokubiminiSerialImpl.hpp.

◆ getName()

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.

◆ getProductName()

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

Gets the product name of the device.

Returns
The product name.

Definition at line 558 of file RokubiminiSerialImpl.hpp.

◆ getReading()

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

Gets the internal reading variable.

Parameters
readingThe variable to store the reading.

Definition at line 898 of file RokubiminiSerialImpl.cpp.

◆ getSerialNumber()

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 280 of file RokubiminiSerialImpl.hpp.

◆ hasError()

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

Checks the connection has errors.

Returns
True if the connection has errors.

Definition at line 391 of file RokubiminiSerialImpl.cpp.

◆ hasFrameSync()

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

Returns if there is frame synchronization with the device.

Returns
True if there is.

Definition at line 537 of file RokubiminiSerialImpl.hpp.

◆ increaseAndCheckTimeoutCounter()

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

Increases the timeout counter and checks if it has passed the maximum available timeouts.

Definition at line 218 of file RokubiminiSerialImpl.cpp.

◆ init()

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 65 of file RokubiminiSerialImpl.cpp.

◆ initSensorCommunication()

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

Initializes communication with the sensor.

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

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:

  • If the baud rate parsed is the maximum available, re-open the port with max baud rate and continue.
  • If the baud rate parsed is the default one, since the port has been opened already with the default baud rate, set the max baud rate, re-open the port with max baud rate and continue.
  • If the baud rate parsed is neither the default nor the maximum, close the serial port (opened with default baud rate), open the port with actual baud rate, set the max baud rate, re-open the port with max baud rate and continue.

Definition at line 465 of file RokubiminiSerialImpl.cpp.

◆ initSerialPort()

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 699 of file RokubiminiSerialImpl.cpp.

◆ isConnected()

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

Checks if the device is connected.

Returns
True if the device is connected.

Definition at line 381 of file RokubiminiSerialImpl.cpp.

◆ isConnecting()

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 386 of file RokubiminiSerialImpl.cpp.

◆ isInConfigMode()

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 401 of file RokubiminiSerialImpl.cpp.

◆ isRunning()

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

Returns if the serial driver is running.

Returns
True if the serial driver is running.

Definition at line 526 of file RokubiminiSerialImpl.hpp.

◆ loadConfig()

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

Loads the configuration of the device.

Returns
True if the operation was successful.

Definition at line 1167 of file RokubiminiSerialImpl.cpp.

◆ openSerialPort()

bool rokubimini::serial::RokubiminiSerialImpl::openSerialPort ( bool  keepOpening)
private

Opens the serial port.

Parameters
keepOpeningSet if there will be multiple attempts or only one.
Returns
True if the serial port was openned successfully.

Definition at line 445 of file RokubiminiSerialImpl.cpp.

◆ parseAcknowledgement()

bool rokubimini::serial::RokubiminiSerialImpl::parseAcknowledgement ( const char &  command_code,
const double &  timeout = 2.0 
)
private

Parses the acknowledgement from the serial device.

Parameters
command_codeThe command code to parse the ACK for.
timeoutThe timeout in seconds to wait before parsing the acknowledgement. By default this is set to 2 seconds.
Returns
True if the acknowledgement was received successfully.

Definition at line 1331 of file RokubiminiSerialImpl.cpp.

◆ parseCommunicationMsgs()

bool rokubimini::serial::RokubiminiSerialImpl::parseCommunicationMsgs ( const double &  timeout = 1.0)

Parses the Communication Messages of the serial sensor.

Parameters
timeoutThe timeout in seconds to wait. By default this is set to 1 seconds.
Returns
True if the operation was successful.

Definition at line 669 of file RokubiminiSerialImpl.cpp.

◆ parseRegexWaitTimeout()

bool rokubimini::serial::RokubiminiSerialImpl::parseRegexWaitTimeout ( RokubiminiSerialResponseRegex reg,
const double &  timeout = 1.0 
)
private

Parses a regex from the serial sensor input stream.

Parameters
regexThe regex to be parsed.
timeoutThe timeout in seconds to wait before parsing the regex. By default this is set to 1 seconds.
Returns
True if the operation was successful.

Definition at line 614 of file RokubiminiSerialImpl.cpp.

◆ pollingWorker()

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

Worker threads for polling the sensors.

Definition at line 790 of file RokubiminiSerialImpl.cpp.

◆ printUserConfig()

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

Prints all the user configurable parameters.

Returns
True if the operation was successful.

Definition at line 1186 of file RokubiminiSerialImpl.cpp.

◆ readDevice()

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 224 of file RokubiminiSerialImpl.cpp.

◆ readSerialNoWait()

bool rokubimini::serial::RokubiminiSerialImpl::readSerialNoWait ( const uint32_t &  numChars,
std::string &  str 
)
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.

Parameters
numCharsThe number of chars to read.
strThe string to read.
Returns
True if new characters were read from the serial device.

Definition at line 637 of file RokubiminiSerialImpl.cpp.

◆ readSerialWaitTimeout()

bool rokubimini::serial::RokubiminiSerialImpl::readSerialWaitTimeout ( const uint32_t &  numChars,
std::string &  str,
const double &  timeout = 1.0 
)
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.

Parameters
numCharsThe number of chars to read.
strThe string to read.
timeoutThe timeout in seconds to wait. By default this is set to 1 seconds.
Returns
True if new characters were read from the serial device.

Definition at line 647 of file RokubiminiSerialImpl.cpp.

◆ resetDataFlags()

void rokubimini::serial::RokubiminiSerialImpl::resetDataFlags ( )

Resets the Data Flags variable currentDataFlagsDiagnostics_.

Definition at line 1287 of file RokubiminiSerialImpl.cpp.

◆ runsAsync()

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

Returns if the driver runs asynchronously.

Returns
True if there is.

Definition at line 569 of file RokubiminiSerialImpl.hpp.

◆ saveConfigParameter()

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 1148 of file RokubiminiSerialImpl.cpp.

◆ sendCalibrationMatrixEntry()

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 742 of file RokubiminiSerialImpl.hpp.

◆ sendCommand()

bool rokubimini::serial::RokubiminiSerialImpl::sendCommand ( const std::string &  command)
private

Sends a command to the serial device.

Parameters
commandThe command to send.
Returns
True if the operation was successful.

Definition at line 1229 of file RokubiminiSerialImpl.cpp.

◆ setAccelerationFilter()

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 328 of file RokubiminiSerialImpl.hpp.

◆ setAccelerationRange()

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 360 of file RokubiminiSerialImpl.hpp.

◆ setAngularRateFilter()

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 344 of file RokubiminiSerialImpl.hpp.

◆ setAngularRateRange()

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 376 of file RokubiminiSerialImpl.hpp.

◆ setCommunicationSetup()

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.

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 1129 of file RokubiminiSerialImpl.cpp.

◆ setConfigMode()

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

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 930 of file RokubiminiSerialImpl.cpp.

◆ setForceTorqueFilter()

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 1039 of file RokubiminiSerialImpl.cpp.

◆ setForceTorqueOffset()

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 1065 of file RokubiminiSerialImpl.cpp.

◆ setHardwareReset()

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

Triggers a hardware reset of the sensor.

Returns
True if the operation was successful.

Definition at line 989 of file RokubiminiSerialImpl.cpp.

◆ setInitMode()

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 1004 of file RokubiminiSerialImpl.cpp.

◆ setRunMode()

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

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 967 of file RokubiminiSerialImpl.cpp.

◆ setRunsAsync()

void rokubimini::serial::RokubiminiSerialImpl::setRunsAsync ( bool  runsAsync)
inline

Sets the runsAsync_ variable.

Parameters
runsAsyncThe variable to set.

Definition at line 580 of file RokubiminiSerialImpl.hpp.

◆ setSensorCalibration()

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 1086 of file RokubiminiSerialImpl.cpp.

◆ setSensorConfiguration()

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 1117 of file RokubiminiSerialImpl.cpp.

◆ shutdown()

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.

◆ startPollingThread()

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

This method starts up the polling thread.

Returns
True if the operation was successful.

Definition at line 97 of file RokubiminiSerialImpl.cpp.

◆ startup()

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

This method starts up communication with the device.

Returns
True if the startup was successful.

Definition at line 109 of file RokubiminiSerialImpl.cpp.

◆ timespecAdd()

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 798 of file RokubiminiSerialImpl.hpp.

◆ timespecToSec()

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

Converts a timespec to seconds.

Parameters
tThe timespec.
Returns
The seconds.

Definition at line 783 of file RokubiminiSerialImpl.hpp.

◆ updateConnectionStatus()

void rokubimini::serial::RokubiminiSerialImpl::updateConnectionStatus ( diagnostic_updater::DiagnosticStatusWrapper stat)

Fills the Device Connection Status (ROS diagnostics).

Parameters
statThe status to be filled with the new diagnostics.

Definition at line 1249 of file RokubiminiSerialImpl.cpp.

◆ updateDataFlags()

void rokubimini::serial::RokubiminiSerialImpl::updateDataFlags ( )

Updates the Data Flags variable currentDataFlagsDiagnostics_.

Definition at line 1279 of file RokubiminiSerialImpl.cpp.

◆ updateRead()

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 191 of file RokubiminiSerialImpl.hpp.

◆ updateWrite()

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 202 of file RokubiminiSerialImpl.hpp.

◆ writeSerial()

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 1353 of file RokubiminiSerialImpl.cpp.

Member Data Documentation

◆ baudRate_

BaudRateStruct rokubimini::serial::RokubiminiSerialImpl::baudRate_
private

The baud rate of the serial communication, as a termios bit mask.

Definition at line 1031 of file RokubiminiSerialImpl.hpp.

◆ connectionState_

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

Internal connection state.

Definition at line 1162 of file RokubiminiSerialImpl.hpp.

◆ connectionThread_

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

Connection thread handle.

Definition at line 1144 of file RokubiminiSerialImpl.hpp.

◆ currentDataFlagsDiagnostics_

std::atomic< DataStatus > rokubimini::serial::RokubiminiSerialImpl::currentDataFlagsDiagnostics_
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.

◆ dataReady_

bool rokubimini::serial::RokubiminiSerialImpl::dataReady_
private

This flag is on when new data are ready to be published.

Definition at line 1343 of file RokubiminiSerialImpl.hpp.

◆ DEFAULT_BAUD_RATE_OPTION

const static uint8_t rokubimini::serial::RokubiminiSerialImpl::DEFAULT_BAUD_RATE_OPTION = 3
staticprivate

Definition at line 1258 of file RokubiminiSerialImpl.hpp.

◆ errorFlags_

ErrorFlags rokubimini::serial::RokubiminiSerialImpl::errorFlags_
private

Flags to indicate errors in serial communication.

Definition at line 1170 of file RokubiminiSerialImpl.hpp.

◆ frame_

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 1122 of file RokubiminiSerialImpl.hpp.

◆ frameCrcErrorCounter_

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

Counter for frames with CRC errors.

Definition at line 1221 of file RokubiminiSerialImpl.hpp.

◆ frameDataStatus_

DataStatus rokubimini::serial::RokubiminiSerialImpl::frameDataStatus_
private

The current frame's Data Status.

Definition at line 1359 of file RokubiminiSerialImpl.hpp.

◆ frameHeader

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

The frame header value.

Definition at line 1112 of file RokubiminiSerialImpl.hpp.

◆ frameOffset_

uint32_t rokubimini::serial::RokubiminiSerialImpl::frameOffset_
private

The frame offset to start reading (in bytes).

Definition at line 1273 of file RokubiminiSerialImpl.hpp.

◆ frameReceivedCounter_

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

Received frame counter.

Definition at line 1203 of file RokubiminiSerialImpl.hpp.

◆ frameSuccessCounter_

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

Correct frames counter.

Definition at line 1212 of file RokubiminiSerialImpl.hpp.

◆ frameSync_

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

Flag that indicates if the frame is synced.

Definition at line 1085 of file RokubiminiSerialImpl.hpp.

◆ frameSyncErrorCounter_

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

Frame sync errors.

Definition at line 1229 of file RokubiminiSerialImpl.hpp.

◆ frameTimestamp_

ros::Time rokubimini::serial::RokubiminiSerialImpl::frameTimestamp_
private

Definition at line 1370 of file RokubiminiSerialImpl.hpp.

◆ FTDI_DRIVER_LATENCY

constexpr static double rokubimini::serial::RokubiminiSerialImpl::FTDI_DRIVER_LATENCY = 0.001
staticconstexprprivate

Definition at line 1293 of file RokubiminiSerialImpl.hpp.

◆ isRunning_

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

Internal flags/indicators.

Internal flag to indicate if the threads are running.

Definition at line 1186 of file RokubiminiSerialImpl.hpp.

◆ MAX_BAUD_RATE_OPTION

const static uint8_t rokubimini::serial::RokubiminiSerialImpl::MAX_BAUD_RATE_OPTION = 4
staticprivate

Definition at line 1265 of file RokubiminiSerialImpl.hpp.

◆ maxCountOpenSerialPort_

unsigned int rokubimini::serial::RokubiminiSerialImpl::maxCountOpenSerialPort_
private

Maximum attempts to open serial port.

Definition at line 1244 of file RokubiminiSerialImpl.hpp.

◆ maxFrameSyncErrorCounts_

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

Maximum acceptable frame sync errors.

Definition at line 1237 of file RokubiminiSerialImpl.hpp.

◆ MAXIMUM_ACCEPTABLE_TIMEOUT

constexpr static double rokubimini::serial::RokubiminiSerialImpl::MAXIMUM_ACCEPTABLE_TIMEOUT = 1.77
staticconstexprprivate

Definition at line 1310 of file RokubiminiSerialImpl.hpp.

◆ modeState_

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

Mode state of the sensor.

Definition at line 1178 of file RokubiminiSerialImpl.hpp.

◆ name_

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

Name of the sensor.

Definition at line 1002 of file RokubiminiSerialImpl.hpp.

◆ newFrameIsAvailable_

std::condition_variable rokubimini::serial::RokubiminiSerialImpl::newFrameIsAvailable_
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.

◆ NSEC_PER_SEC

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

Definition at line 1251 of file RokubiminiSerialImpl.hpp.

◆ placeholder_

RxFrame rokubimini::serial::RokubiminiSerialImpl::placeholder_
private

A placeholder to save unfinished frames.

Definition at line 1281 of file RokubiminiSerialImpl.hpp.

◆ pollingSyncErrorCounter_

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

Internal statistics and error counters.

Synchronization error counter.

Definition at line 1195 of file RokubiminiSerialImpl.hpp.

◆ pollingThread_

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

Polling thread handle.

Definition at line 1153 of file RokubiminiSerialImpl.hpp.

◆ port_

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

The serial port to connect to.

Definition at line 1022 of file RokubiminiSerialImpl.hpp.

◆ productName_

std:string rokubimini::serial::RokubiminiSerialImpl::productName_
private

The product name of the device.

Definition at line 1040 of file RokubiminiSerialImpl.hpp.

◆ readingMutex_

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

Mutex prohibiting simultaneous access the internal Reading variable.

Definition at line 1058 of file RokubiminiSerialImpl.hpp.

◆ readTimeout_

double rokubimini::serial::RokubiminiSerialImpl::readTimeout_
private

The timeout to read from device (in seconds).

Definition at line 1318 of file RokubiminiSerialImpl.hpp.

◆ runInThreadedMode_

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

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

Definition at line 1135 of file RokubiminiSerialImpl.hpp.

◆ runsAsync_

std::atomic< bool > rokubimini::serial::RokubiminiSerialImpl::runsAsync_
private

The flag that represents whether the driver runs asynchronously or not.

Definition at line 1351 of file RokubiminiSerialImpl.hpp.

◆ serialImplReading_

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 1013 of file RokubiminiSerialImpl.hpp.

◆ serialMutex_

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

Mutex prohibiting simultaneous access to Serial device.

Definition at line 1067 of file RokubiminiSerialImpl.hpp.

◆ serialNumber_

uint32_t rokubimini::serial::RokubiminiSerialImpl::serialNumber_
private

The serial number of the device.

Definition at line 1049 of file RokubiminiSerialImpl.hpp.

◆ TIMEOUT_MARGIN

constexpr static double rokubimini::serial::RokubiminiSerialImpl::TIMEOUT_MARGIN = 0.15
staticconstexprprivate

Definition at line 1301 of file RokubiminiSerialImpl.hpp.

◆ timeoutCounter_

unsigned int rokubimini::serial::RokubiminiSerialImpl::timeoutCounter_
private

Timeout counter.

Definition at line 1326 of file RokubiminiSerialImpl.hpp.

◆ usbFileDescriptor_

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

The USB file descriptor.

Definition at line 1076 of file RokubiminiSerialImpl.hpp.

◆ usbStreamIn_

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

Input stream for the USB file descriptor.

Definition at line 1094 of file RokubiminiSerialImpl.hpp.

◆ usbStreamOut_

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

Output stream for the USB file descriptor.

Definition at line 1103 of file RokubiminiSerialImpl.hpp.


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


rokubimini_serial
Author(s):
autogenerated on Sat Apr 15 2023 02:53:58