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>

List of all members.

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

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)

Public Member Functions

 cDSA (int debug_level=0, int port=1, char const *device_format_string="/dev/ttyS%d")
void Close (void)
 Set the framerate of the remote DSACON32m controller to 0 and close connection to it.
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.
sTactileSensorFrame const & GetFrame () const
 return a reference to the latest tactile sensor frame without reading from remote DSACON32m
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.
sSensitivityInfo GetMatrixSensitivity (int matrix_no) throw (cDSAException*)
UInt16 GetMatrixThreshold (int matrix_no) throw (cDSAException*)
sSensorInfo const & GetSensorInfo (void) const
 Return a reference to the sSensorInfo read from the remote DSACON32m controller.
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()
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) throw (cDSAException*)
void SetMatrixSensitivity (int matrix_no, double sensitivity, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false) throw (cDSAException*)
void SetMatrixThreshold (int matrix_no, UInt16 threshold, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false) throw (cDSAException*)
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.
 ~cDSA ()
 Destructur: clean up and delete dynamically allocated memory.

Static Public Member Functions

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

Public Attributes

struct cDSA::sSensitivityInfo __packed__
 Structure to hold info about the sensitivity settings of one sensor patch.
struct cDSA::sMatrixInfo __packed__
 A data structure describing a single sensor matrix connected to the remote DSACON32m controller.
struct cDSA::sSensorInfo __packed__
 A data structure describing the sensor info about the remote DSACON32m controller.
struct cDSA::sControllerInfo __packed__
 A data structure describing the controller info about the remote DSACON32m controller.

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)
void ReadSensorInfo (sSensorInfo *_sensor_info)
void WriteCommand (UInt8 command)
void WriteCommandWithPayload (UInt8 command, UInt8 *payload, UInt16 payload_len)

Protected Attributes

struct cDSA::sResponse __packed__
 data structure for storing responses from the remote DSACON32m controller
double calib_pressure
double calib_voltage
 see calib_pressure
cRS232 comm_interface
 the serial RS232 communication interface to use
tTexel contact_area_cell_threshold
 threshold of texel cell value for detecting contacts with GetContactArea
tTexel contact_force_cell_threshold
 threshold of texel cell value for detecting forces with GetContactForce
sControllerInfo controller_info
 the controller info read from the remote DSACON32m controller
cDBG dbg
 A stream object to print coloured debug messages.
bool do_RLE
 flag, true if data should be sent Run Length Encoded by the remote DSACON32m controller
double force_factor
 additional calibration factor for forces in GetContactForce
sTactileSensorFrame frame
 the latest frame received from the remote DSACON32m controller
sMatrixInfomatrix_info
 the matrix infos read from the remote DSACON32m controller
int nb_cells
 The total number of sensor cells.
long read_timeout_us
 default timeout used for reading in us
sSensorInfo sensor_info
 the sensor info read from the remote DSACON32m controller
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

Private Member Functions

void ReadAndCheckErrorResponse (char const *msg)
double VoltageToPressure (double voltage)

Friends

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.

Definition at line 109 of file dsa.h.


Member Typedef Documentation

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

Definition at line 113 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 116 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.

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.
cDSA::~cDSA (  ) 

Destructur: clean up and delete dynamically allocated memory.


Member Function Documentation

void cDSA::Close ( void   ) 

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

static char const* cDSA::ErrorCodeToString ( UInt16  error_code  )  [inline, static]

Definition at line 629 of file dsa.h.

static 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
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 605 of file dsa.h.

double cDSA::GetContactArea ( int  m  ) 
sContactInfo cDSA::GetContactInfo ( int  m  ) 
sControllerInfo const& cDSA::GetControllerInfo ( void   )  const [inline]

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

Definition at line 438 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 460 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 596 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 452 of file dsa.h.

sSensitivityInfo cDSA::GetMatrixSensitivity ( int  matrix_no  )  throw (cDSAException*)

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] (0.0 is minimum, 1.0 is maximum sensitivity) fact_sens - the factory sensitivity as float [0.0 .. 1.0] (0.0 is minimum, 1.0 is maximum sensitivity)

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
UInt16 cDSA::GetMatrixThreshold ( int  matrix_no  )  throw (cDSAException*)

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.
sSensorInfo const& cDSA::GetSensorInfo ( void   )  const [inline]

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

Definition at line 445 of file dsa.h.

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

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()

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

Parse a full frame response from remote DSA

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.

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.

void cDSA::QueryMatrixInfos ( void   )  [protected]

Query all matrix infos

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.

void cDSA::ReadAndCheckErrorResponse ( char const *  msg  )  [private]
void cDSA::ReadControllerInfo ( sControllerInfo _controller_info  )  [protected]

Read and parse a controller info response from the remote DSA

void cDSA::ReadFrame ( sTactileSensorFrame frame_p  )  [protected]

read and parse a full frame response from remote DSA

void cDSA::ReadMatrixInfo ( sMatrixInfo _matrix_info  )  [protected]

Read and parse a matrix info response from the remote DSA

void cDSA::ReadResponse ( sResponse response  )  [protected]

Read any response from the remote DSACON32m

  • 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
void cDSA::ReadSensorInfo ( sSensorInfo _sensor_info  )  [protected]

Read and parse a sensor info response from the remote DSA

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. 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
void cDSA::SetFramerateRetries ( UInt16  framerate,
bool  do_RLE = true,
bool  do_data_acquisition = true,
unsigned int  retries = 0,
bool  ignore_exceptions = false 
) throw (cDSAException*)

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
void cDSA::SetMatrixSensitivity ( int  matrix_no,
double  sensitivity,
bool  do_all_matrices = false,
bool  do_reset = false,
bool  do_persistent = false 
) throw (cDSAException*)

Send command to set matrix sensitivity to sensitivity as float [0.0 .. 1.0] (0.0 is minimum, 1.0 is maximum sensitivity). 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.
void cDSA::SetMatrixThreshold ( int  matrix_no,
UInt16  threshold,
bool  do_all_matrices = false,
bool  do_reset = false,
bool  do_persistent = false 
) throw (cDSAException*)

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.
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 467 of file dsa.h.

double cDSA::VoltageToPressure ( double  voltage  )  [private]
void cDSA::WriteCommand ( UInt8  command  )  [inline, protected]

Definition at line 334 of file dsa.h.

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

Friends And Related Function Documentation

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

Member Data Documentation

struct cDSA::sResponse cDSA::__packed__ [protected]

data structure for storing responses from the remote DSACON32m controller

Structure to hold info about the sensitivity settings of one sensor patch.

A data structure describing a single sensor matrix connected to the remote DSACON32m controller.

A data structure describing the sensor info about the remote DSACON32m controller.

A data structure describing the controller info about the remote DSACON32m controller.

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 327 of file dsa.h.

double cDSA::calib_voltage [protected]

see calib_pressure

Definition at line 329 of file dsa.h.

the serial RS232 communication interface to use

Definition at line 285 of file dsa.h.

threshold of texel cell value for detecting contacts with GetContactArea

Definition at line 315 of file dsa.h.

threshold of texel cell value for detecting forces with GetContactForce

Definition at line 318 of file dsa.h.

the controller info read from the remote DSACON32m controller

Definition at line 291 of file dsa.h.

cDBG cDSA::dbg [protected]

A stream object to print coloured debug messages.

Definition at line 282 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 288 of file dsa.h.

double cDSA::force_factor [protected]

additional calibration factor for forces in GetContactForce

Definition at line 321 of file dsa.h.

the latest frame received from the remote DSACON32m controller

Definition at line 300 of file dsa.h.

the matrix infos read from the remote DSACON32m controller

Definition at line 297 of file dsa.h.

int cDSA::nb_cells [protected]

The total number of sensor cells.

Definition at line 303 of file dsa.h.

long cDSA::read_timeout_us [protected]

default timeout used for reading in us

Definition at line 309 of file dsa.h.

the sensor info read from the remote DSACON32m controller

Definition at line 294 of file dsa.h.

UInt32 cDSA::start_dsa [protected]

Definition at line 312 of file dsa.h.

Definition at line 311 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 306 of file dsa.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


cob_sdh
Author(s): Florian Weisshardt
autogenerated on Fri Jan 11 10:03:55 2013