#include <ati_force_torque_hw_rs485.h>
|
| 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 () |
|
| ForceTorqueSensorHW () |
|
| ForceTorqueSensorHW (int type, std::string path, int baudrate, int base_identifier) |
|
virtual bool | readDiagnosticADCVoltages (int index, short int &value) |
|
virtual | ~ForceTorqueSensorHW () |
|
ATIForceTorqueSensorHWRS485::ATIForceTorqueSensorHWRS485 |
( |
| ) |
|
ATIForceTorqueSensorHWRS485::ATIForceTorqueSensorHWRS485 |
( |
std::string |
device_path, |
|
|
int |
device_baudrate, |
|
|
int |
base_identifier |
|
) |
| |
ATIForceTorqueSensorHWRS485::~ATIForceTorqueSensorHWRS485 |
( |
| ) |
|
|
virtual |
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
-
type | Not used in this implementation |
path | Device path on the system |
baudrate | Baudrate, with which to communicate. Will only accept 1250000, 115200 or 19200 |
base_identifier | Sensor 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 |
bool ATIForceTorqueSensorHWRS485::OpenRawConnection |
( |
| ) |
|
|
protected |
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 |
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 |
bool ATIForceTorqueSensorHWRS485::ReadSessionID |
( |
uint16_t & |
sessionID | ) |
const |
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 |
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
-
- 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
-
- 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
-
value | The baurate (in baud/sec). Allowed values are: 1250000, 115200, 19200 |
setVolatile | if 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] | ) |
|
bool ATIForceTorqueSensorHWRS485::SetSessionID |
( |
const uint16_t |
sessionID | ) |
|
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
-
lock | True, 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 |
( |
| ) |
|
bool ATIForceTorqueSensorHWRS485::StopStreaming |
( |
| ) |
|
void ATIForceTorqueSensorHWRS485::StrainGaugeToForce |
( |
const int & |
sg0, |
|
|
const int & |
sg1, |
|
|
const int & |
sg2, |
|
|
const int & |
sg3, |
|
|
const int & |
sg4, |
|
|
const int & |
sg5 |
|
) |
| |
bool ATIForceTorqueSensorHWRS485::ValidateFTData |
( |
const uint8_t(&) |
buf[26] | ) |
const |
|
protected |
unsigned int ATIForceTorqueSensorHWRS485::bufferSize = 0 |
|
private |
long unsigned int ATIForceTorqueSensorHWRS485::bytesRead |
|
private |
std::string ATIForceTorqueSensorHWRS485::forceUnitStr |
|
private |
ros::Time ATIForceTorqueSensorHWRS485::lastValidTimeStamp |
|
private |
std::mutex ATIForceTorqueSensorHWRS485::m_buffer_mutex |
|
private |
long unsigned int ATIForceTorqueSensorHWRS485::m_bufferTimeout = 10000000 |
|
private |
bool ATIForceTorqueSensorHWRS485::m_isStreaming = false |
|
private |
uint8_t ATIForceTorqueSensorHWRS485::m_ModbusBaseIdentifier |
|
private |
int ATIForceTorqueSensorHWRS485::m_ModbusBaudrate |
|
private |
modbus_t* ATIForceTorqueSensorHWRS485::m_modbusCtrl |
|
private |
Eigen::MatrixXf ATIForceTorqueSensorHWRS485::m_mXCalibMatrix |
|
private |
boost::thread ATIForceTorqueSensorHWRS485::m_readThread |
|
private |
int ATIForceTorqueSensorHWRS485::m_rs485 |
|
private |
std::string ATIForceTorqueSensorHWRS485::m_RS485Device |
|
private |
Eigen::MatrixXf ATIForceTorqueSensorHWRS485::m_vForceData |
|
private |
ros::Time ATIForceTorqueSensorHWRS485::readStart |
|
private |
uint8_t ATIForceTorqueSensorHWRS485::streamBuf[26] |
|
private |
std::string ATIForceTorqueSensorHWRS485::torqueUnitStr |
|
private |
The documentation for this class was generated from the following files: