61 #define DSA_MAX_PREAMBLE_SEARCH (2*3*(6*(14+13)) + 16) 125 E_FEATURE_NOT_SUPPORTED,
130 E_INSUFFICIENT_RESOURCES,
132 E_CMD_NOT_ENOUGH_PARAMS,
153 #pragma pack(push,1) // for VCC (MS Visual Studio) we have to set the necessary 1 byte packing with this pragma 219 #pragma pack(pop) // for VCC (MS Visual Studio) restore normal packing 273 #pragma pack(push,1) // for VCC (MS Visual Studio) we have to set the necessary 1 byte packing with this pragma 285 max_payload_size = _max_payload_size;
289 #pragma pack(pop) // for VCC (MS Visual Studio) restore normal packing 349 WriteCommandWithPayload( command,
NULL, 0 );
407 void QueryMatrixInfo(
sMatrixInfo* _matrix_info,
int matrix_no );
413 void QueryMatrixInfos(
void );
442 cDSA(
int debug_level=0,
int port=1,
char const* device_format_string=
"/dev/ttyS%d" );
463 cDSA(
int debug_level,
char const* _tcp_adr,
int _tcp_port=13000,
double _timeout=1.0 );
473 return controller_info;
487 assert( 0 <= m && m <= (
int ) sensor_info.
nb_matrices );
488 return matrix_info[m];
542 void SetFramerate(
UInt16 framerate,
bool do_RLE=
true,
bool do_data_acquisition=
true );
556 void SetFramerateRetries(
UInt16 framerate,
bool do_RLE=
true,
bool do_data_acquisition=
true,
unsigned int retries=0,
bool ignore_exceptions=
false );
592 void SetMatrixSensitivity(
int matrix_no,
594 bool do_all_matrices=
false,
596 bool do_persistent=
false );
615 void SetMatrixThreshold(
int matrix_no,
617 bool do_all_matrices=
false,
619 bool do_persistent=
false );
630 UInt16 GetMatrixThreshold(
int matrix_no );
635 tTexel GetTexel(
int m,
int x,
int y )
const;
644 return fi * 2 + part;
653 return ((
unsigned long) (start_pc.
Elapsed()*1000.0)) - (frame_p->
timestamp - start_dsa);
656 double GetContactArea(
int m );
659 double VoltageToPressure(
double voltage );
661 void ReadAndCheckErrorResponse(
char const* msg,
UInt8 command_id );
666 void Init(
int debug_level );
700 void FlushInput(
long timeout_us_first,
long timeout_us_subsequent );
718 VCC_EXPORT std::ostream &
operator<<( std::ostream &stream,
cDSA const &dsa );
cDBG dbg
A stream object to print coloured debug messages.
double calib_voltage
see calib_pressure
double force_factor
additional calibration factor for forces in GetContactForce
Interface of auxilliary utility functions for SDHLibrary-CPP.
VCC_EXPORT std::ostream & operator<<(std::ostream &stream, cDSA::sControllerInfo const &controller_info)
UInt32 timestamp
the timestamp of the frame. Use GetAgeOfFrame() to set this into relation with the time of the PC...
A class to print colored debug messages.
sMatrixInfo const & GetMatrixInfo(int m) const
Return a reference to the sMatrixInfo of matrix m read from the remote DSACON32m controller.
uint8_t UInt8
unsigned integer, size 1 Byte (8 Bit)
cSerialBase * com
the communication interface to use
sResponse(UInt8 *_payload, int _max_payload_size)
constructor to init pointer and max size
tTexel contact_force_cell_threshold
threshold of texel cell value for detecting forces with GetContactForce
sTactileSensorFrame frame
the latest frame received from the remote DSACON32m controller
Derived exception class for low-level DSA related exceptions.
long read_timeout_us
default timeout used for reading in us
static char const * ErrorCodeToString(UInt16 error_code)
double Elapsed(void) const
Return time in seconds elapsed between the time stored in the object and now.
UInt16 error_code
0000h, if successful, otherwise error code
This file contains interface to cCRC, a class to handle CRC calculation.
int GetMatrixIndex(int fi, int part)
UInt16 tTexel
data type for a single 'texel' (tactile sensor element)
eDSAErrorCode
error codes returned by the remote DSACON32m tactile sensor controller
This file contains interface and implementation of class #SDH::cDBG, a class for colorfull debug mess...
Interface of the exception base class #SDH::cSDHLibraryException and #SDH::cMsg.
uint32_t UInt32
unsigned integer, size 4 Byte (32 Bit)
Low-level communication class to access a serial port.
#define NAMESPACE_SDH_START
SDH::cDSA is the end user interface class to access the DSACON32m, the tactile sensor controller of t...
Base class for exceptions in the SDHLibrary-CPP.
tTexel contact_area_cell_threshold
threshold of texel cell value for detecting contacts with GetContactArea
data structure for storing responses from the remote DSACON32m controller
UInt16 error_code
0000h, if successful, otherwise error code
cDSAException(cMsg const &_msg)
sTactileSensorFrame(void)
constructor
A data structure describing the sensor info about the remote DSACON32m controller.
sSensorInfo sensor_info
the sensor info read from the remote DSACON32m controller
int * texel_offset
an array with the offsets of the first texel of all matrices into the whole frame ...
bool acquiring_single_frame
flag, true if user requested acquiring of a single frame. Needed for DSACON32m firmware-bug workaroun...
tTexel * texel
an 2D array of tTexel elements. Use GetTexel() for easy access to specific individual elements...
sTactileSensorFrame const & GetFrame() const
return a reference to the latest tactile sensor frame without reading from remote DSACON32m ...
Interface of class #SDH::cRS232, a class to access serial RS232 port on cygwin/linux.
Structure to hold info about the sensitivity settings of one sensor patch.
#define SDH__attribute__(...)
#define NAMESPACE_SDH_END
bool do_RLE
flag, true if data should be sent Run Length Encoded by the remote DSACON32m controller ...
This file contains settings to make the SDHLibrary compile on differen systems:
Very simple class to measure elapsed time.
sControllerInfo controller_info
the controller info read from the remote DSACON32m controller
A data structure describing a full tactile sensor frame read from the remote DSACON32m controller...
sMatrixInfo * matrix_info
the matrix infos read from the remote DSACON32m controller
sSensorInfo const & GetSensorInfo(void) const
Return a reference to the sSensorInfo read from the remote DSACON32m controller.
Class for short, fixed maximum length text messages.
sTactileSensorFrame const & UpdateFrame()
read the tactile sensor frame from remote DSACON32m and return a reference to it. A command to query ...
sControllerInfo const & GetControllerInfo(void) const
Return a reference to the sControllerInfo read from the remote DSACON32m controller.
Implementation of class #SDH::cRS232, a class to access serial RS232 port with VCC compiler on Window...
unsigned long GetAgeOfFrame(sTactileSensorFrame *frame_p)
int32_t Int32
signed integer, size 4 Byte (32 Bit)
void WriteCommand(UInt8 command)
A data structure describing a single sensor matrix connected to the remote DSACON32m controller...
uint16_t UInt16
unsigned integer, size 2 Byte (16 Bit)
int nb_cells
The total number of sensor cells.
A data structure describing the controller info about the remote DSACON32m controller.