Public Member Functions | Protected Member Functions | Private Attributes | List of all members
ATIForceTorqueSensorHWRS485 Class Reference

#include <ati_force_torque_hw_rs485.h>

Inheritance diagram for ATIForceTorqueSensorHWRS485:
Inheritance graph
[legend]

Public Member Functions

 ATIForceTorqueSensorHWRS485 ()
 
 ATIForceTorqueSensorHWRS485 (std::string device_path, int device_baudrate, int base_identifier)
 
bool Close ()
 
virtual bool init ()
 
virtual bool initCommunication (int type, std::string path, int baudrate, int base_identifier)
 
bool ReadFTCalibrationData (const unsigned int calibrationNumber=1)
 
virtual bool readFTData (int statusCode, double &Fx, double &Fy, double &Fz, double &Tx, double &Ty, double &Tz)
 
bool ReadSessionID (uint16_t &sessionID) const
 
bool ReadStatusWord () const
 
bool Reset ()
 
bool SetActiveGain (const uint16_t ag0, const uint16_t ag1, const uint16_t ag2, const uint16_t ag3, const uint16_t ag4, const uint16_t ag5) const
 
bool SetActiveOffset (const uint16_t ao0, const uint16_t ao1, const uint16_t ao2, const uint16_t ao3, const uint16_t ao4, const uint16_t ao5) const
 
bool SetBaudRate (const int value, const bool setVolatile=true)
 
void SetCalibMatrix (const float(&matrix)[6][6])
 
bool SetSessionID (const uint16_t sessionID)
 
bool StartStreaming ()
 
bool StopStreaming ()
 
void StrainGaugeToForce (const int &sg0, const int &sg1, const int &sg2, const int &sg3, const int &sg4, const int &sg5)
 
virtual ~ATIForceTorqueSensorHWRS485 ()
 
- Public Member Functions inherited from hardware_interface::ForceTorqueSensorHW
 ForceTorqueSensorHW ()
 
 ForceTorqueSensorHW (int type, std::string path, int baudrate, int base_identifier)
 
virtual bool readDiagnosticADCVoltages (int index, short int &value)
 
virtual ~ForceTorqueSensorHW ()
 

Protected Member Functions

bool initRS485 ()
 
bool OpenRawConnection ()
 
bool ReadData ()
 
void ReadDataLoop ()
 
bool SendStopSequence ()
 
bool SetStorageLock (const bool lock) const
 
bool ValidateFTData (const uint8_t(&buf)[26]) const
 

Private Attributes

unsigned int bufferSize = 0
 
long unsigned int bytesRead
 
std::string forceUnitStr
 
ros::Time lastValidTimeStamp
 
GageVector m_buffer
 
std::mutex m_buffer_mutex
 
long unsigned int m_bufferTimeout = 10000000
 
CalibrationData m_calibrationData
 
bool m_isStreaming = false
 
uint8_t m_ModbusBaseIdentifier
 
int m_ModbusBaudrate
 
modbus_tm_modbusCtrl
 
Eigen::MatrixXf m_mXCalibMatrix
 
boost::thread m_readThread
 
int m_rs485
 
std::string m_RS485Device
 
Eigen::MatrixXf m_vForceData
 
ros::Time readStart
 
uint8_t streamBuf [26]
 
std::string torqueUnitStr
 

Detailed Description

Definition at line 130 of file ati_force_torque_hw_rs485.h.

Constructor & Destructor Documentation

ATIForceTorqueSensorHWRS485::ATIForceTorqueSensorHWRS485 ( )

By default, the baudrate is set to 1.250.000

Definition at line 73 of file ati_force_torque_hw_rs485.cpp.

ATIForceTorqueSensorHWRS485::ATIForceTorqueSensorHWRS485 ( std::string  device_path,
int  device_baudrate,
int  base_identifier 
)
Parameters
device_path
device_baudrate
base_identifier

Definition at line 84 of file ati_force_torque_hw_rs485.cpp.

ATIForceTorqueSensorHWRS485::~ATIForceTorqueSensorHWRS485 ( )
virtual

Standard destructor. Closes all active connections

Definition at line 94 of file ati_force_torque_hw_rs485.cpp.

Member Function Documentation

bool ATIForceTorqueSensorHWRS485::Close ( )

Closes the current modbus communication with the sensor

Returns
Returns true if the operation was successful

Definition at line 640 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::init ( )
virtual

Initializes communication with the sensor using the current configuration, reads calibration data and sets the calibration matrix Use initCommunication(...) prior to this, in order to set the communication parameters

Returns
True, if the initialization was successful

Reimplemented from hardware_interface::ForceTorqueSensorHW.

Definition at line 124 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::initCommunication ( int  type,
std::string  path,
int  baudrate,
int  base_identifier 
)
virtual

Sets the parameters used for Modbus communication

Parameters
typeNot used in this implementation
pathDevice path on the system
baudrateBaudrate, with which to communicate. Will only accept 1250000, 115200 or 19200
base_identifierSensor ID. Default value is 0xA
Returns
True, if all parameters were valid

Reimplemented from hardware_interface::ForceTorqueSensorHW.

Definition at line 106 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::initRS485 ( )
protected

Openes modbus connection to the sensor

Returns
Returns true, if the operation was successful

Definition at line 175 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::OpenRawConnection ( )
protected

Definition at line 770 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::ReadData ( )
protected

Reads a set of force torque measurements in the form of a GageVector from the connected sensor and stores it in the local m_buffer variable

Returns
Returns true, if the operation was successful. Returns false if the checksum was invalid or no data was received

Definition at line 853 of file ati_force_torque_hw_rs485.cpp.

void ATIForceTorqueSensorHWRS485::ReadDataLoop ( )
protected

Definition at line 833 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::ReadFTCalibrationData ( const unsigned int  calibrationNumber = 1)

Reads the calibration data from the FT sensor and stores it

@param calibrationNumber: The register number of the calibration data to read. Can be set to a value between 1 and 16, according to 8.3.2
Returns
Returns true, if the operation was successful

Definition at line 250 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::readFTData ( int  statusCode,
double &  Fx,
double &  Fy,
double &  Fz,
double &  Tx,
double &  Ty,
double &  Tz 
)
virtual
Parameters
statusCode
Fx
Fy
Fz
Tx
Ty
Tz
Returns

Reimplemented from hardware_interface::ForceTorqueSensorHW.

Definition at line 689 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::ReadSessionID ( uint16_t &  sessionID) const
Parameters
sessionID
Returns

Definition at line 667 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::ReadStatusWord ( ) const

Reads the current status from the sensor This should be done after an error occurred, to determine the exact cause of the problem The result will then be printed to the console

Returns
Returns true if the status word could be read successfully

Definition at line 492 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::Reset ( )

Closes the current connection (if open) and opens a new connection

Returns
Returns true if the operation was successful

Definition at line 624 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SendStopSequence ( )
protected

Definition at line 952 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SetActiveGain ( const uint16_t  ag0,
const uint16_t  ag1,
const uint16_t  ag2,
const uint16_t  ag3,
const uint16_t  ag4,
const uint16_t  ag5 
) const

Transmits the active gain values to the sensor. You need to unlock the storage lock first before being able to set the values

Parameters
ag0
ag1
ag2
ag3
ag4
ag5
Returns

Definition at line 459 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SetActiveOffset ( const uint16_t  ao0,
const uint16_t  ao1,
const uint16_t  ao2,
const uint16_t  ao3,
const uint16_t  ao4,
const uint16_t  ao5 
) const

Transmits the active offset values to the sensor. You need to unlock the storage lock first before being able to set the values

Parameters
ao0
ao1
ao2
ao3
ao4
ao5
Returns

Definition at line 476 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SetBaudRate ( const int  value,
const bool  setVolatile = true 
)

Set the communication baudrate of the sensor If the baudrate change was successful, resets the communication and creates a new connection using the given baudrate

Parameters
valueThe baurate (in baud/sec). Allowed values are: 1250000, 115200, 19200
setVolatileif this flag is set, the baudrate will only be changed for this current session. If not, the sensor's baudrate will be changed permanently
Returns
Returns true if the operation was successful

Definition at line 570 of file ati_force_torque_hw_rs485.cpp.

void ATIForceTorqueSensorHWRS485::SetCalibMatrix ( const float(&)  matrix[6][6])

Sets the calibration matrix

Parameters
matrixthe new calibration matrix as a floating point array

Definition at line 992 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SetSessionID ( const uint16_t  sessionID)
Parameters
sessionID
Returns

Definition at line 648 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::SetStorageLock ( const bool  lock) const
protected

Sets the storage mode of the connected sensor (according to specifications in 8.3.1. of the sensor's use manual)

Parameters
lockTrue, to lock the sensor's storage, false to unlock it
Returns
Returns true, if the operation was successful

Definition at line 424 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::StartStreaming ( )
Returns

Definition at line 730 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::StopStreaming ( )
Returns

Definition at line 938 of file ati_force_torque_hw_rs485.cpp.

void ATIForceTorqueSensorHWRS485::StrainGaugeToForce ( const int &  sg0,
const int &  sg1,
const int &  sg2,
const int &  sg3,
const int &  sg4,
const int &  sg5 
)
Parameters
sg0
sg1
sg2
sg3
sg4
sg5
Returns

Definition at line 970 of file ati_force_torque_hw_rs485.cpp.

bool ATIForceTorqueSensorHWRS485::ValidateFTData ( const uint8_t(&)  buf[26]) const
protected

Definition at line 912 of file ati_force_torque_hw_rs485.cpp.

Member Data Documentation

unsigned int ATIForceTorqueSensorHWRS485::bufferSize = 0
private

Definition at line 328 of file ati_force_torque_hw_rs485.h.

long unsigned int ATIForceTorqueSensorHWRS485::bytesRead
private

Definition at line 322 of file ati_force_torque_hw_rs485.h.

std::string ATIForceTorqueSensorHWRS485::forceUnitStr
private

Definition at line 334 of file ati_force_torque_hw_rs485.h.

ros::Time ATIForceTorqueSensorHWRS485::lastValidTimeStamp
private

Definition at line 325 of file ati_force_torque_hw_rs485.h.

GageVector ATIForceTorqueSensorHWRS485::m_buffer
private

Definition at line 330 of file ati_force_torque_hw_rs485.h.

std::mutex ATIForceTorqueSensorHWRS485::m_buffer_mutex
private

Definition at line 331 of file ati_force_torque_hw_rs485.h.

long unsigned int ATIForceTorqueSensorHWRS485::m_bufferTimeout = 10000000
private

Definition at line 321 of file ati_force_torque_hw_rs485.h.

CalibrationData ATIForceTorqueSensorHWRS485::m_calibrationData
private

Definition at line 324 of file ati_force_torque_hw_rs485.h.

bool ATIForceTorqueSensorHWRS485::m_isStreaming = false
private

Definition at line 319 of file ati_force_torque_hw_rs485.h.

uint8_t ATIForceTorqueSensorHWRS485::m_ModbusBaseIdentifier
private

Definition at line 313 of file ati_force_torque_hw_rs485.h.

int ATIForceTorqueSensorHWRS485::m_ModbusBaudrate
private

Definition at line 314 of file ati_force_torque_hw_rs485.h.

modbus_t* ATIForceTorqueSensorHWRS485::m_modbusCtrl
private

Definition at line 309 of file ati_force_torque_hw_rs485.h.

Eigen::MatrixXf ATIForceTorqueSensorHWRS485::m_mXCalibMatrix
private

Definition at line 316 of file ati_force_torque_hw_rs485.h.

boost::thread ATIForceTorqueSensorHWRS485::m_readThread
private

Definition at line 332 of file ati_force_torque_hw_rs485.h.

int ATIForceTorqueSensorHWRS485::m_rs485
private

Definition at line 310 of file ati_force_torque_hw_rs485.h.

std::string ATIForceTorqueSensorHWRS485::m_RS485Device
private

Definition at line 312 of file ati_force_torque_hw_rs485.h.

Eigen::MatrixXf ATIForceTorqueSensorHWRS485::m_vForceData
private

Definition at line 317 of file ati_force_torque_hw_rs485.h.

ros::Time ATIForceTorqueSensorHWRS485::readStart
private

Definition at line 327 of file ati_force_torque_hw_rs485.h.

uint8_t ATIForceTorqueSensorHWRS485::streamBuf[26]
private

Definition at line 326 of file ati_force_torque_hw_rs485.h.

std::string ATIForceTorqueSensorHWRS485::torqueUnitStr
private

Definition at line 335 of file ati_force_torque_hw_rs485.h.


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


ati_force_torque
Author(s): Denis Štogl, Alexander Bubeck
autogenerated on Thu Sep 17 2020 03:18:35