Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends | List of all members
cDSA Class Reference

SDH::cDSA is the end user interface class to access the DSACON32m, the tactile sensor controller of the SDH. More...

#include <dsa.h>

Classes

struct  sContactInfo
 Structure to hold info about the contact of one sensor patch. More...
 
struct  sControllerInfo
 A data structure describing the controller info about the remote DSACON32m controller. More...
 
struct  sMatrixInfo
 A data structure describing a single sensor matrix connected to the remote DSACON32m controller. More...
 
struct  sResponse
 data structure for storing responses from the remote DSACON32m controller More...
 
struct  sSensitivityInfo
 Structure to hold info about the sensitivity settings of one sensor patch. More...
 
struct  sSensorInfo
 A data structure describing the sensor info about the remote DSACON32m controller. More...
 
struct  sTactileSensorFrame
 A data structure describing a full tactile sensor frame read from the remote DSACON32m controller. More...
 

Public Types

enum  eDSAErrorCode {
  E_SUCCESS, E_NOT_AVAILABLE, E_NO_SENSOR, E_NOT_INITIALIZED,
  E_ALREADY_RUNNING, E_FEATURE_NOT_SUPPORTED, E_INCONSISTENT_DATA, E_TIMEOUT,
  E_READ_ERROR, E_WRITE_ERROR, E_INSUFFICIENT_RESOURCES, E_CHECKSUM_ERROR,
  E_CMD_NOT_ENOUGH_PARAMS, E_CMD_UNKNOWN, E_CMD_FORMAT_ERROR, E_ACCESS_DENIED,
  E_ALREADY_OPEN, E_CMD_FAILED, E_CMD_ABORTED, E_INVALID_HANDLE,
  E_DEVICE_NOT_FOUND, E_DEVICE_NOT_OPENED, E_IO_ERROR, E_INVALID_PARAMETER,
  E_INDEX_OUT_OF_BOUNDS, E_CMD_PENDING, E_OVERRUN, E_RANGE_ERROR
}
 error codes returned by the remote DSACON32m tactile sensor controller More...
 
typedef UInt16 tTexel
 data type for a single 'texel' (tactile sensor element) More...
 

Public Member Functions

 cDSA (int debug_level=0, int port=1, char const *device_format_string="/dev/ttyS%d")
 
 cDSA (int debug_level, char const *_tcp_adr, int _tcp_port=13000, double _timeout=1.0)
 
void Close (void)
 Set the framerate of the remote DSACON32m controller to 0 and close connection to it. More...
 
unsigned long GetAgeOfFrame (sTactileSensorFrame *frame_p)
 
double GetContactArea (int m)
 
sContactInfo GetContactInfo (int m)
 
sControllerInfo const & GetControllerInfo (void) const
 Return a reference to the sControllerInfo read from the remote DSACON32m controller. More...
 
sTactileSensorFrame const & GetFrame () const
 return a reference to the latest tactile sensor frame without reading from remote DSACON32m More...
 
int GetMatrixIndex (int fi, int part)
 
sMatrixInfo const & GetMatrixInfo (int m) const
 Return a reference to the sMatrixInfo of matrix m read from the remote DSACON32m controller. More...
 
sSensitivityInfo GetMatrixSensitivity (int matrix_no)
 
UInt16 GetMatrixThreshold (int matrix_no)
 
sSensorInfo const & GetSensorInfo (void) const
 Return a reference to the sSensorInfo read from the remote DSACON32m controller. More...
 
tTexel GetTexel (int m, int x, int y) const
 
void Open (void)
 (Re-)open connection to DSACON32m controller, this is called by the constructor automatically, but is still usefull to call after a call to Close() More...
 
struct cDSA::sSensitivityInfo SDH__attribute__ ((__packed__))
 
struct cDSA::sControllerInfo SDH__attribute__ ((__packed__))
 
struct cDSA::sSensorInfo SDH__attribute__ ((__packed__))
 
struct cDSA::sMatrixInfo SDH__attribute__ ((__packed__))
 
void SetFramerate (UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true)
 
void SetFramerateRetries (UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true, unsigned int retries=0, bool ignore_exceptions=false)
 
void SetMatrixSensitivity (int matrix_no, double sensitivity, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false)
 
void SetMatrixThreshold (int matrix_no, UInt16 threshold, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false)
 
sTactileSensorFrame const & UpdateFrame ()
 read the tactile sensor frame from remote DSACON32m and return a reference to it. A command to query the frame (periodically) must have been sent before. More...
 
 ~cDSA ()
 Destructur: clean up and delete dynamically allocated memory. More...
 

Static Public Member Functions

static char const * ErrorCodeToString (eDSAErrorCode error_code)
 
static char const * ErrorCodeToString (UInt16 error_code)
 

Public Attributes

bool m_read_another
 
struct VCC_EXPORT cDSA::sTactileSensorFrame SDH__attribute__
 

Protected Member Functions

void ParseFrame (sResponse *response, sTactileSensorFrame *frame_p)
 
void QueryControllerInfo (sControllerInfo *_controller_info)
 
void QueryMatrixInfo (sMatrixInfo *_matrix_info, int matrix_no)
 
void QueryMatrixInfos (void)
 
void QuerySensorInfo (sSensorInfo *_sensor_info)
 
void ReadControllerInfo (sControllerInfo *_controller_info)
 
void ReadFrame (sTactileSensorFrame *frame_p)
 
void ReadMatrixInfo (sMatrixInfo *_matrix_info)
 
void ReadResponse (sResponse *response, UInt8 command_id)
 
void ReadSensorInfo (sSensorInfo *_sensor_info)
 
struct cDSA::sResponse SDH__attribute__ ((__packed__))
 
void WriteCommand (UInt8 command)
 
void WriteCommandWithPayload (UInt8 command, UInt8 *payload, UInt16 payload_len)
 

Protected Attributes

double calib_pressure
 
double calib_voltage
 see calib_pressure More...
 
cSerialBasecom
 the communication interface to use More...
 
tTexel contact_area_cell_threshold
 threshold of texel cell value for detecting contacts with GetContactArea More...
 
tTexel contact_force_cell_threshold
 threshold of texel cell value for detecting forces with GetContactForce More...
 
sControllerInfo controller_info
 the controller info read from the remote DSACON32m controller More...
 
cDBG dbg
 A stream object to print coloured debug messages. More...
 
bool do_RLE
 flag, true if data should be sent Run Length Encoded by the remote DSACON32m controller More...
 
double force_factor
 additional calibration factor for forces in GetContactForce More...
 
sTactileSensorFrame frame
 the latest frame received from the remote DSACON32m controller More...
 
sMatrixInfomatrix_info
 the matrix infos read from the remote DSACON32m controller More...
 
int nb_cells
 The total number of sensor cells. More...
 
long read_timeout_us
 default timeout used for reading in us More...
 
sSensorInfo sensor_info
 the sensor info read from the remote DSACON32m controller More...
 
UInt32 start_dsa
 
cSimpleTime start_pc
 
int * texel_offset
 an array with the offsets of the first texel of all matrices into the whole frame More...
 

Private Member Functions

void FlushInput (long timeout_us_first, long timeout_us_subsequent)
 
void Init (int debug_level)
 
void ReadAndCheckErrorResponse (char const *msg, UInt8 command_id)
 
double VoltageToPressure (double voltage)
 

Private Attributes

bool acquiring_single_frame
 flag, true if user requested acquiring of a single frame. Needed for DSACON32m firmware-bug workaround. More...
 

Friends

VCC_EXPORT std::ostream & operator<< (std::ostream &stream, cDSA::sResponse const &response)
 

Detailed Description

SDH::cDSA is the end user interface class to access the DSACON32m, the tactile sensor controller of the SDH.

Class to communicate with the tactile sensor controller DSACON32m of the SDH

Bug:
cDSAException: Checksum Error on Windows console While communicating with the tactile sensor controller a "cDSAException: Checksum Error" might be thrown once in a while. This seems to happen only when the program is started from a native windows command console (cmd.exe), but not e.g. when the program is started from a cygwin console. Strange. Workaround is to catch the exception and ignore the frame.
=> Resolved in SDHLibrary-C++ v0.0.2.1
Problem was an overrun of the windows input buffer, e.g. on heavy processor load.

Definition at line 111 of file dsa.h.

Member Typedef Documentation

data type for a single 'texel' (tactile sensor element)

Definition at line 115 of file dsa.h.

Member Enumeration Documentation

error codes returned by the remote DSACON32m tactile sensor controller

Enumerator
E_SUCCESS 
E_NOT_AVAILABLE 
E_NO_SENSOR 
E_NOT_INITIALIZED 
E_ALREADY_RUNNING 
E_FEATURE_NOT_SUPPORTED 
E_INCONSISTENT_DATA 
E_TIMEOUT 
E_READ_ERROR 
E_WRITE_ERROR 
E_INSUFFICIENT_RESOURCES 
E_CHECKSUM_ERROR 
E_CMD_NOT_ENOUGH_PARAMS 
E_CMD_UNKNOWN 
E_CMD_FORMAT_ERROR 
E_ACCESS_DENIED 
E_ALREADY_OPEN 
E_CMD_FAILED 
E_CMD_ABORTED 
E_INVALID_HANDLE 
E_DEVICE_NOT_FOUND 
E_DEVICE_NOT_OPENED 
E_IO_ERROR 
E_INVALID_PARAMETER 
E_INDEX_OUT_OF_BOUNDS 
E_CMD_PENDING 
E_OVERRUN 
E_RANGE_ERROR 

Definition at line 118 of file dsa.h.

Constructor & Destructor Documentation

cDSA::cDSA ( int  debug_level = 0,
int  port = 1,
char const *  device_format_string = "/dev/ttyS%d" 
)

Constructor for cDSA. This constructs a cDSA object to communicate with the remote DSACON32m controller within the SDH via RS232.

The connection is opened and established, and the sensor, controller and matrix info is queried from the remote DSACON32m controller. This initialization may take up to 9 seconds, since the DSACON32m controller needs > 8 seconds for "booting". If the SDH is already powered for some time then this will be much quicker.

Parameters
debug_level- the level of debug messages to be printed:
  • if > 0 (1,2,3...) then debug messages of cDSA itself are printed
  • if > 1 (2,3,...) then debug messages of the low level communication interface object are printed too
port- the RS232 port to use for communication. (port 0 = ttyS0 = COM1, port 1 = ttyS1 = COM2, ...)
device_format_string- a format string (C string) for generating the device name, like "/dev/ttyS%d" (default) or "/dev/ttyUSB%d". Must contain a d where the port number should be inserted. This char array is duplicated on construction. When compiled with VCC (MS-Visual C++) then this is not used.

Definition at line 596 of file dsa.cpp.

cDSA::cDSA ( int  debug_level,
char const *  _tcp_adr,
int  _tcp_port = 13000,
double  _timeout = 1.0 
)

Constructor for cDSA. This constructs a cDSA object to communicate with the remote DSACON32m controller within the SDH via TCP/IP (ethernet).

The connection is opened and established, and the sensor, controller and matrix info is queried from the remote DSACON32m controller. This initialization may take up to 9 seconds, since the DSACON32m controller needs > 8 seconds for "booting". If the SDH is already powered for some time then this will be much quicker.

Parameters
debug_level- the level of debug messages to be printed:
  • if > 0 (1,2,3...) then debug messages of cDSA itself are printed
  • if > 1 (2,3,...) then debug messages of the low level communication interface object are printed too
_tcp_adr: The tcp host address of the SDH. Either a numeric IP as string or a hostname
_tcp_port: the tcp port number on the SDH to connect to
_timeout: The timeout to use:
  • <= 0 : wait forever (default)
  • T : wait for T seconds

Definition at line 622 of file dsa.cpp.

cDSA::~cDSA ( )

Destructur: clean up and delete dynamically allocated memory.

Definition at line 724 of file dsa.cpp.

Member Function Documentation

void cDSA::Close ( void  )

Set the framerate of the remote DSACON32m controller to 0 and close connection to it.

Definition at line 739 of file dsa.cpp.

char const * cDSA::ErrorCodeToString ( eDSAErrorCode  error_code)
static

Return a short string description for error_code

Parameters
error_code- error code as returned from the remote DSACON32m tactile sensor controller
Returns
short string description for error_code

Definition at line 1073 of file dsa.cpp.

static char const* cDSA::ErrorCodeToString ( UInt16  error_code)
inlinestatic

Definition at line 680 of file dsa.h.

void cDSA::FlushInput ( long  timeout_us_first,
long  timeout_us_subsequent 
)
private

Cleanup communication line: read all available bytes with timeout_us_first timeout in us for first byte and timeout_us_subsequent timeoutin us for subsequent bytes

Parameters
timeout_us_first- timeout in us for first byte
timeout_us_subsequent- timeout in us for subsequent bytes

The push mode of the DSACON32m must be switched off on call since else the method will not return.

Definition at line 647 of file dsa.cpp.

unsigned long cDSA::GetAgeOfFrame ( sTactileSensorFrame frame_p)
inline

return age of frame in ms (time in ms from frame sampling until now)

Definition at line 651 of file dsa.h.

double cDSA::GetContactArea ( int  m)

Return contact area in mm*mm for matrix with index m

Definition at line 982 of file dsa.cpp.

cDSA::sContactInfo cDSA::GetContactInfo ( int  m)

Return a sContactInfo struct (force,cog_x,cog_y,area) of contact force and center of gravity and contact area of that force for matrix with index m

Definition at line 1026 of file dsa.cpp.

sControllerInfo const& cDSA::GetControllerInfo ( void  ) const
inline

Return a reference to the sControllerInfo read from the remote DSACON32m controller.

Definition at line 471 of file dsa.h.

sTactileSensorFrame const& cDSA::GetFrame ( ) const
inline

return a reference to the latest tactile sensor frame without reading from remote DSACON32m

Definition at line 493 of file dsa.h.

int cDSA::GetMatrixIndex ( int  fi,
int  part 
)
inline

return the matrix index of the sensor matrix attached to finger with index fi [1..3] and part [0,1] = [proximal,distal]

Definition at line 642 of file dsa.h.

sMatrixInfo const& cDSA::GetMatrixInfo ( int  m) const
inline

Return a reference to the sMatrixInfo of matrix m read from the remote DSACON32m controller.

Definition at line 485 of file dsa.h.

cDSA::sSensitivityInfo cDSA::GetMatrixSensitivity ( int  matrix_no)

Send command to get matrix sensitivity. Returns sensitivities of matrix no matrix_no.

A struct is returned containing the members error_code - see DSACON32 Command Set Reference Manual adj_flags - see DSACON32 Command Set Reference Manual cur_sens - the currently set sensitivity as float 0.0 .. 1.0 fact_sens - the factory sensitivity as float 0.0 .. 1.0

Raises a cDSAException in case of invalid responses from the remote DSACON32m controller.

Bug:
With DSACON32m firmware R218 and before this did not work, instead the factory default (0.5) was always reported
=> Resolved in DSACON32m firmware R268

Definition at line 879 of file dsa.cpp.

UInt16 cDSA::GetMatrixThreshold ( int  matrix_no)

Send command to get matrix threshold. Returns threshold of matrix no matrix_no.

Returns
threshold - the currently set threshold as integer [0 .. 4095] (0 is minimum, 4095 is maximum threshold)

Raises a cDSAException in case of invalid responses from the remote DSACON32m controller.

Remarks
Getting the matrix threshold is only possible if the DSACON32m firmware is R268 or above.

Definition at line 934 of file dsa.cpp.

sSensorInfo const& cDSA::GetSensorInfo ( void  ) const
inline

Return a reference to the sSensorInfo read from the remote DSACON32m controller.

Definition at line 478 of file dsa.h.

cDSA::tTexel cDSA::GetTexel ( int  m,
int  x,
int  y 
) const

Return texel value at column x row y of matrix m of the last frame

Definition at line 965 of file dsa.cpp.

void cDSA::Init ( int  debug_level)
private

Common private initialization stuff.

Definition at line 577 of file dsa.cpp.

void cDSA::Open ( void  )

(Re-)open connection to DSACON32m controller, this is called by the constructor automatically, but is still usefull to call after a call to Close()

Definition at line 671 of file dsa.cpp.

void cDSA::ParseFrame ( sResponse response,
sTactileSensorFrame frame_p 
)
protected

Parse a full frame response from remote DSA

Definition at line 495 of file dsa.cpp.

void cDSA::QueryControllerInfo ( sControllerInfo _controller_info)
protected

Send command to resquest controller info from remote DSACON32m. Read and parse the response from the remote DSACON32m.

Definition at line 434 of file dsa.cpp.

void cDSA::QueryMatrixInfo ( sMatrixInfo _matrix_info,
int  matrix_no 
)
protected

Send command to request matrix info from remote DSACON32m. Read and parse the response from the remote DSACON32m.

Definition at line 450 of file dsa.cpp.

void cDSA::QueryMatrixInfos ( void  )
protected

Query all matrix infos

Definition at line 458 of file dsa.cpp.

void cDSA::QuerySensorInfo ( sSensorInfo _sensor_info)
protected

Send command to request sensor info from remote DSACON32m. Read and parse the response from the remote DSACON32m.

Definition at line 442 of file dsa.cpp.

void cDSA::ReadAndCheckErrorResponse ( char const *  msg,
UInt8  command_id 
)
private

Definition at line 748 of file dsa.cpp.

void cDSA::ReadControllerInfo ( sControllerInfo _controller_info)
protected

Read and parse a controller info response from the remote DSA

Definition at line 314 of file dsa.cpp.

void cDSA::ReadFrame ( sTactileSensorFrame frame_p)
protected

read and parse a full frame response from remote DSA

Definition at line 353 of file dsa.cpp.

void cDSA::ReadMatrixInfo ( sMatrixInfo _matrix_info)
protected

Read and parse a matrix info response from the remote DSA

Definition at line 341 of file dsa.cpp.

void cDSA::ReadResponse ( sResponse response,
UInt8  command_id 
)
protected

Read any response from the remote DSACON32m, expect the command_id as command id

  • tries to find the preamble within the next at most DSA_MAX_PREAMBLE_SEARCH bytes from the device
  • reads the packet id and size
  • reads all data indicated by the size read
  • if there is enough space in the payload of the response then the received data is stored there if there is not enough space in the payload of the response then the data is received but forgotten (to keep the communication line clear)
  • if sent, the CRC checksum is read and the data is checked. For invalid data an exception is thrown

Definition at line 169 of file dsa.cpp.

void cDSA::ReadSensorInfo ( sSensorInfo _sensor_info)
protected

Read and parse a sensor info response from the remote DSA

Definition at line 329 of file dsa.cpp.

struct cDSA::sControllerInfo cDSA::SDH__attribute__ ( (__packed__)  )
struct cDSA::sSensorInfo cDSA::SDH__attribute__ ( (__packed__)  )
struct cDSA::sMatrixInfo cDSA::SDH__attribute__ ( (__packed__)  )
struct cDSA::sSensitivityInfo cDSA::SDH__attribute__ ( (__packed__)  )
struct cDSA::sResponse cDSA::SDH__attribute__ ( (__packed__)  )
protected
void cDSA::SetFramerate ( UInt16  framerate,
bool  do_RLE = true,
bool  do_data_acquisition = true 
)

Set the framerate for querying full frames.

Parameters
framerate- rate of frames.
do_RLE- flag, if true then use RLE (run length encoding) for sending frames
do_data_acquisition- flag, enable or disable data acquisition. Must be true if you want to get new frames
  • Use framerate=0 and do_data_acquisition=false to make the remote DSACON32m in SDH stop sending frames
  • Use framerate=0 and do_data_acquisition=true to read a single frame
  • Use framerate>0 and do_data_acquisition=true to make the remote DSACON32m in SDH send frames at the highest possible rate (for now: 30 FPS (frames per second)).
Bug:
SCHUNK-internal bugzilla ID: Bug 680
With DSACON32m firmware R276 and after and SDHLibrary-C++ v0.0.1.15 and before stopping of the sending did not work.
=> Resolved in SDHLibrary-C++ v0.0.1.16
Bug:
SCHUNK-internal bugzilla ID: Bug 680
With DSACON32m firmware before R276 and SDHLibrary-C++ v0.0.1.16 and before acquiring of single frames did not work
=> Resolved in SDHLibrary-C++ v0.0.1.17
Bug:
SCHUNK-internal bugzilla ID: Bug 703
With DSACON32m firmware R288 and before and SDHLibrary-C++ v0.0.2.1 and before tactile sensor frames could not be read reliably in single frame mode.
=> Resolved in DSACON32m firmware 2.9.0.0
=> Resolved in SDHLibrary-C++ v0.0.2.1 with workaround for older DSACON32m firmwares

Definition at line 766 of file dsa.cpp.

void cDSA::SetFramerateRetries ( UInt16  framerate,
bool  do_RLE = true,
bool  do_data_acquisition = true,
unsigned int  retries = 0,
bool  ignore_exceptions = false 
)

Set the framerate for querying full frames.

Parameters
framerate- rate of frames. 0 will make the remote DSACON32m in SDH stop sending frames, any value > 0 will make the remote DSACON32m in SDH send frames at the highest possible rate (for now: 30 FPS (frames per second)).
do_RLE- flag, if true then use RLE (run length encoding) for sending frames
do_data_acquisition- flag, enable or disable data acquisition. Must be true if you want to get new frames
retries- number of times the sending will be retried in case of an error (like timeout while waiting for response)
ignore_exceptions- flag, if true then exceptions are ignored in case of error. After retries tries the function just returns even in case of an error

Definition at line 810 of file dsa.cpp.

void cDSA::SetMatrixSensitivity ( int  matrix_no,
double  sensitivity,
bool  do_all_matrices = false,
bool  do_reset = false,
bool  do_persistent = false 
)

Send command to set matrix sensitivity to sensitivity as float 0.0 .. 1.0. If do_all_matrices is true then the sensitivity is set for all matrices. If do_reset is true then the sensitivity is reset to the factory default. If do_persistent is true then the sensitivity is saved persistently to configuration memory and will thus remain after the next power off/power on cycle and will become the new factory default value. If do_persistent is false (default) then the value will be reset to default on the next power off/power on cycle

Warning
PLEASE NOTE: the maximum write endurance of the configuration memory is about 100.000 times!

Raises a cDSAException in case of invalid responses from the remote DSACON32m controller.

Remarks
Setting the matrix sensitivity persistently is only possible if the DSACON32m firmware is R268 or above.

Definition at line 836 of file dsa.cpp.

void cDSA::SetMatrixThreshold ( int  matrix_no,
UInt16  threshold,
bool  do_all_matrices = false,
bool  do_reset = false,
bool  do_persistent = false 
)

Send command to set matrix threshold to threshold as integer [0 .. 4095] (0 is minimum, 4095 is maximum threshold). If do_all_matrices is true then the threshold is set for all matrices. If do_reset is true then the threshold is reset to the factory default. If do_persistent is true then the threshold is saved persistently to configuration memory and will thus remain after the next power off/power on cycle and will become the new factory default value. If do_persistent is false (default) then the value will be reset to default on the next power off/power on cycle

Warning
PLEASE NOTE: the maximum write endurance of the configuration memory is about 100.000 times!

Raises a cDSAException in case of invalid responses from the remote DSACON32m controller.

Remarks
Getting the matrix threshold is only possible if the DSACON32m firmware is R268 or above.

Definition at line 902 of file dsa.cpp.

sTactileSensorFrame const& cDSA::UpdateFrame ( )
inline

read the tactile sensor frame from remote DSACON32m and return a reference to it. A command to query the frame (periodically) must have been sent before.

Definition at line 500 of file dsa.h.

double cDSA::VoltageToPressure ( double  voltage)
private

Return a pressure in for cell voltage. pressure is in N/(mm*mm)

Definition at line 1005 of file dsa.cpp.

void cDSA::WriteCommand ( UInt8  command)
inlineprotected

Definition at line 347 of file dsa.h.

void cDSA::WriteCommandWithPayload ( UInt8  command,
UInt8 payload,
UInt16  payload_len 
)
protected

Definition at line 101 of file dsa.cpp.

Friends And Related Function Documentation

VCC_EXPORT std::ostream& operator<< ( std::ostream &  stream,
cDSA::sResponse const &  response 
)
friend

Definition at line 1185 of file dsa.cpp.

Member Data Documentation

bool cDSA::acquiring_single_frame
private

flag, true if user requested acquiring of a single frame. Needed for DSACON32m firmware-bug workaround.

Definition at line 687 of file dsa.h.

double cDSA::calib_pressure
protected

For the voltage to pressure conversion in _VoltageToPressure() enter one pressure/voltage measurement here (from demo-dsa.py –calibration):

Definition at line 340 of file dsa.h.

double cDSA::calib_voltage
protected

see calib_pressure

Definition at line 342 of file dsa.h.

cSerialBase* cDSA::com
protected

the communication interface to use

Definition at line 298 of file dsa.h.

tTexel cDSA::contact_area_cell_threshold
protected

threshold of texel cell value for detecting contacts with GetContactArea

Definition at line 328 of file dsa.h.

tTexel cDSA::contact_force_cell_threshold
protected

threshold of texel cell value for detecting forces with GetContactForce

Definition at line 331 of file dsa.h.

sControllerInfo cDSA::controller_info
protected

the controller info read from the remote DSACON32m controller

Definition at line 304 of file dsa.h.

cDBG cDSA::dbg
protected

A stream object to print coloured debug messages.

Definition at line 295 of file dsa.h.

bool cDSA::do_RLE
protected

flag, true if data should be sent Run Length Encoded by the remote DSACON32m controller

Definition at line 301 of file dsa.h.

double cDSA::force_factor
protected

additional calibration factor for forces in GetContactForce

Definition at line 334 of file dsa.h.

sTactileSensorFrame cDSA::frame
protected

the latest frame received from the remote DSACON32m controller

Definition at line 313 of file dsa.h.

bool cDSA::m_read_another

flag, if True then the ReadFrame() function will read tactile sensor frames until a timeout occurs. This will ignore intermediate frames as long as new ones are available. This was usefull some time in the past, or if you have a slow computer that cannot handle incoming frames fast enough. If False then any completely read valid frame will be reported. With new computers and fast communication like via TCP this should remain at "False".

Definition at line 267 of file dsa.h.

sMatrixInfo* cDSA::matrix_info
protected

the matrix infos read from the remote DSACON32m controller

Definition at line 310 of file dsa.h.

int cDSA::nb_cells
protected

The total number of sensor cells.

Definition at line 316 of file dsa.h.

long cDSA::read_timeout_us
protected

default timeout used for reading in us

Definition at line 322 of file dsa.h.

struct VCC_EXPORT cDSA::sTactileSensorFrame cDSA::SDH__attribute__
sSensorInfo cDSA::sensor_info
protected

the sensor info read from the remote DSACON32m controller

Definition at line 307 of file dsa.h.

UInt32 cDSA::start_dsa
protected

Definition at line 325 of file dsa.h.

cSimpleTime cDSA::start_pc
protected

Definition at line 324 of file dsa.h.

int* cDSA::texel_offset
protected

an array with the offsets of the first texel of all matrices into the whole frame

Definition at line 319 of file dsa.h.


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


sdhlibrary_cpp
Author(s): Dirk Osswald
autogenerated on Sun Aug 18 2019 03:42:21