Go to the documentation of this file.
  104     int bytes_written = 0;
 
  109     char* buffer = 
new char[ payload_len+8 ];
 
  114     char buffer[ payload_len + 8 ]; 
 
  116     buffer[0] = (
UInt8) 0xaa;
 
  117     buffer[1] = (
UInt8) 0xaa;
 
  118     buffer[2] = (
UInt8) 0xaa;
 
  120     buffer[4] = ((
UInt8*) &payload_len)[0];
 
  121     buffer[5] = ((
UInt8*) &payload_len)[1];
 
  123     if ( payload_len > 0)
 
  131     for ( i=0; i < payload_len; i++)
 
  137     if ( payload_len > 0)
 
  140         len = payload_len + 8;
 
  150     bytes_written = 
com->
write( buffer, len );
 
  164     if ( bytes_written != len )
 
  165         throw new cDSAException( 
cMsg( 
"Could only write %d/%d bytes to DSACON32m", bytes_written, len ) );
 
  171     assert( response != 
NULL );
 
  173     int retries_frames = 0;
 
  174     while ( retries_frames++ < 5 )
 
  180         int   nb_preamble_bytes = 0;
 
  181         ssize_t bytes_read = 0;
 
  191                 dbg << 
"Caught cSerialBaseException " << e->
what() << 
", rethrowing as cDSAException timeout\n";
 
  195             if ( bytes_read == 0 )
 
  196                 throw new cDSAException( 
cMsg( 
"Timeout while reading preamble from remote DSACON32m controller" ) );
 
  202                 dbg << 
"found valid preamble byte no " << nb_preamble_bytes << 
"\n";
 
  206                 nb_preamble_bytes = 0;
 
  207                 dbg << 
"ignoring invalid preamble byte " << int(
byte) << 
"\n";
 
  210             found = nb_preamble_bytes == 3;
 
  214             throw new cDSAException( 
cMsg( 
"Could not find valid preamble in %ld data bytes from remote DSACON32m controller", bytes_read ) );
 
  220         if ( bytes_read != 3 )
 
  222             throw new cDSAException( 
cMsg( 
"Could only read %ld/3 header bytes from remote DSACON32m controller", bytes_read ) );
 
  233             char* buffer = 
new char[ response->
size+2 ];
 
  238                 char buffer[ response->
size+2 ];
 
  242                 dbg << 
"Read and ignored " << nb_bytes_ignored << 
" bytes of response " << *response << 
"\n";
 
  264             throw new cDSAException( 
cMsg( 
"Unexpected response. Expected command_id 0x%02x with up to %d payload bytes, but got command_id 0x%02x with %d payload bytes", (
int) command_id, (
int) response->
max_payload_size, (
int) response->
packet_id, response->
size ) );
 
  271         if ( bytes_read != response->
size )
 
  273             throw new cDSAException( 
cMsg( 
"Could only read %ld/%d payload bytes from remote DSACON32m controller", bytes_read, response->
size ) );
 
  279         if ( response->
size > 0 )
 
  284             bytes_read = 
com->
Read( (
void*) &checksum_received, 
sizeof( checksum_received ), 
read_timeout_us, 
false );
 
  285             if ( bytes_read != 
sizeof( checksum_received ) )
 
  286                 throw new cDSAException( 
cMsg( 
"Could only read %ld/2 checksum bytes from remote DSACON32m controller", bytes_read ) );
 
  291             for ( i=0; i < response->
size; i++ )
 
  294             if ( checksum_received != checksum_calculated.
GetCRC() )
 
  296                 dbg << 
"Checksum Error, got 0x" << std::hex << checksum_received << 
" but expected 0x" << std::hex << checksum_calculated.
GetCRC() << 
"\n";
 
  297                 dbg << 
"response = " << *response << 
"\n";
 
  300                 throw new cDSAException( 
cMsg( 
"Checksum Error, got 0x%x but expected 0x%x", checksum_received, checksum_calculated.
GetCRC() ) );
 
  303                 dbg << 
"Checksum OK\n";
 
  309     throw new cDSAException( 
cMsg( 
"Retried %d times but could not get expected response with command_id 0x%02x and up to %d payload bytes.", retries_frames, (
int) command_id, (
int) response->
max_payload_size ) );
 
  316     sResponse response( (
UInt8*) _controller_info, 
sizeof( *_controller_info ) );
 
  323     if ( 18 != response.
size )
 
  324         throw new cDSAException( 
cMsg( 
"Response with controllerinfo has unexpected size %d (expected %d)", response.
size, 18 ) );
 
  331     sResponse response( (
UInt8*) _sensor_info, 
sizeof( *_sensor_info ) );
 
  335     if ( response.
size != 
sizeof( *_sensor_info ) )
 
  336         throw new cDSAException( 
cMsg( 
"Response with sensorinfo has unexpected size %d (expected %ld)", response.
size, 
sizeof(*_sensor_info) ) );
 
  343     sResponse response( (
UInt8*) _matrix_info, 
sizeof( *_matrix_info ) );
 
  347     if ( response.
size != 
sizeof( *_matrix_info ) )
 
  348         throw new cDSAException( 
cMsg( 
"Response with matrixinfo has unexpected size %d (expected %ld)", response.
size, 
sizeof(*_matrix_info) ) );
 
  365     UInt8 buffer[ buffersize ];
 
  367     sResponse response( buffer, buffersize );
 
  380     while ( read_another )
 
  392             read_another = 
false;
 
  426         dbg << 
"switching off acquiring single frames\n";
 
  527         dbg.
PDM( 
"ParseFrame: elapsed ms pc,dsa = %6u,%6u  %6u   age %6lu\n", (
unsigned int) (diff_pc*1000.0), (
unsigned int) diff_dsa, (
unsigned int)(((
unsigned int)(diff_pc*1000.0))-diff_dsa), 
GetAgeOfFrame(frame_p) );
 
  541         while (i+1 < response->
size)
 
  544             v = rle_unit & 0x0fff;
 
  551                     frame_p->
texel[ j ] = v;
 
  556             i += 
sizeof( rle_unit );
 
  579     dbg << 
"Debug messages of class cDSA are printed like this.\n";
 
  586     assert( 
sizeof( 
sResponse )   == 7 + 
sizeof( 
char* ) );  
 
  596 cDSA::cDSA( 
int debug_level, 
int port, 
char const* device_format_string )
 
  598     m_read_another(false),
 
  606     read_timeout_us (1000000), 
 
  609     contact_area_cell_threshold (10),
 
  610     contact_force_cell_threshold (10),
 
  612     calib_pressure (0.000473), 
 
  613     calib_voltage (592.1),     
 
  614     acquiring_single_frame (false)
 
  617     com = 
new cRS232( port, 115200, 1.0, device_format_string );
 
  622 cDSA::cDSA( 
int debug_level, 
char const* _tcp_adr, 
int _tcp_port, 
double _timeout )
 
  624     m_read_another(false),
 
  632     read_timeout_us (1000000), 
 
  635     contact_area_cell_threshold (10),
 
  636     contact_force_cell_threshold (10),
 
  638     calib_pressure (0.000473), 
 
  639     calib_voltage (592.1),     
 
  640     acquiring_single_frame (false)
 
  649     int bytes_read, bytes_read_total = 0;
 
  650     long timeout_us = timeout_us_first;
 
  654             bytes_read = 
com->
Read( &
byte, 4096, timeout_us, 
true );
 
  663         bytes_read_total += bytes_read;
 
  664         timeout_us = timeout_us_subsequent;
 
  665     } 
while (bytes_read > 0);
 
  666     dbg << 
"ignoring " << bytes_read_total << 
" old bytes of garbage from device\n";
 
  754     if ( response.
size != 2 )
 
  756         throw new cDSAException( 
cMsg( 
"Invalid response from DSACON32m for %s, expected 2 bytes but got %d", msg, response.
size ) );
 
  768     dbg << 
"cDSA::SetFramerate, setting framerate to " << framerate << 
" do_data_acquisition= " << do_data_acquisition << 
"\n";
 
  771     if ( do_data_acquisition )
 
  795     buffer[1] = ((
UInt8*) &framerate)[0];
 
  796     buffer[2] = ((
UInt8*) &framerate)[1];
 
  800     dbg << 
"acknowledge ok\n";
 
  802     if ( framerate==0 && do_data_acquisition )
 
  822             if ( retries-- == 0  &&  !ignore_exceptions )
 
  825             dbg << 
"ignoring Caught exception: " << e->
what() << 
"\n";
 
  831     } 
while ( retries>0 );
 
  838                                  bool do_all_matrices,
 
  843 #pragma pack(push,1)  // for VCC (MS Visual Studio) we have to set the necessary 1 byte packing with this pragma 
  845     struct sSetSensitivity
 
  852 #pragma pack(pop)   // for VCC (MS Visual Studio) restore normal packing 
  855     sSetSensitivity set_sensitivity;
 
  857     set_sensitivity.flags = 0;
 
  859         set_sensitivity.flags |= (1<<7);
 
  860     if ( do_all_matrices )
 
  861         set_sensitivity.flags |= (1<<1);
 
  863         set_sensitivity.flags |= (1<<0);
 
  865     set_sensitivity.matrix_no   = (
UInt8) matrix_no;
 
  866     set_sensitivity.sensitivity = (float) sensitivity;
 
  871     if ( ! do_persistent )
 
  874     dbg << 
"SetMatrixSensitivity ok\n";
 
  885     sResponse response( (
UInt8*) &sensitivity_info, 
sizeof( sensitivity_info ) );
 
  888     if ( response.
size != 
sizeof( sensitivity_info ) )
 
  890         throw new cDSAException( 
cMsg( 
"Invalid response from DSACON32m for cDSA::GetMatrixSensitivity(), expected %ld bytes but got %d", 
sizeof( sensitivity_info ), response.
size ) );
 
  894         throw new cDSAException( 
cMsg( 
"Error response from DSACON32m for cDSA::GetMatrixSensitivity(), errorcode = %d (%s)", sensitivity_info.error_code, 
ErrorCodeToString( sensitivity_info.error_code ) ) );
 
  896     dbg << 
"GetMatrixSensitivity ok\n";
 
  898     return sensitivity_info;
 
  904                                bool do_all_matrices,
 
  914     if ( do_all_matrices )
 
  921     buffer[1] = matrix_no & 0xff;
 
  922     memcpy( &(buffer[2]), &threshold, 
sizeof( threshold ) );
 
  926     if ( ! do_persistent )
 
  929     dbg << 
"SetMatrixThreshold ok\n";
 
  942     sResponse response( buffer, 
sizeof(buffer) );
 
  946     if ( response.
size != 
sizeof( buffer ) )
 
  948         throw new cDSAException( 
cMsg( 
"cDSA::GetMatrixThreshold() Invalid response from DSACON32m, expected %ld bytes but got %d", 
sizeof( buffer ), response.
size ) );
 
  956     dbg << 
"GetMatrixThreshold ok\n";
 
  959     memcpy( (
void*) &threshold, (
void*) &(buffer[2]), 
sizeof( threshold ) );
 
 1029     double sum_pressures = 0.0;
 
 1047                 sum_x += double(x) * p;
 
 1048                 sum_y += double(y) * p;
 
 1057     if ( sum_pressures != 0.0 )
 
 1106         return "unknown error_code";
 
 1112 #define PRINT_MEMBER( _s, _var, _member )                       \ 
 1113     (_s) << "  " << #_member << "=" << _var._member << "\n" 
 1115 #define PRINT_MEMBER_HEX( _s, _var, _member )                       \ 
 1116     (_s) << "  " << #_member << "=0x" << std::hex << int(_var._member) << std::dec << "\n" 
 1123     stream << 
"sControllerInfo:\n";
 
 1140     stream << 
"sSensorInfo:\n";
 
 1153     stream << 
"sMatrixInfo:\n";
 
 1159     stream << 
"  " << 
"uid" << 
"={";
 
 1161     for ( i=0; i<(
sizeof(matrix_info.
uid)/
sizeof(matrix_info.
uid[0])); i++ )
 
 1162         stream << 
" 0x" << std::hex << std::setfill(
'0') << std::setw(2) << int(matrix_info.
uid[i]);
 
 1164     stream << 
"  " << 
"reserved" << 
"={";
 
 1165     for ( i=0; i<(
sizeof(matrix_info.
reserved)/
sizeof(matrix_info.
reserved[0])); i++ )
 
 1166         stream << 
" 0x" << std::hex << std::setfill(
'0') << std::setw(2) << int(matrix_info.
reserved[i]);
 
 1167     stream << 
"}\n" << std::dec << std::setfill(
' ');
 
 1187     stream << 
"sResponse:\n";
 
 1192     stream << 
"  payload=";
 
 1199             stream << 
"\n    " << std::setw(3) << i << 
": " << hbs;
 
 1215     stream << 
"cDSA.frame:";
 
 1219     unsigned int m, x, y;
 
 1222         stream <<  
"  matrix " << m << 
":\n";
 
 1226             stream << std::setw( 2 ) << y << 
"| ";
 
 1229                 stream << std::setw( 4 ) << dsa.
GetTexel( m, x, y ) << 
" ";
 
  
@ eDSA_GET_SENSITIVITY_ADJUSTMENT_INFO
@ eDSA_SET_PROPERTIES_SAMPLE_RATE
A data structure describing a single sensor matrix connected to the remote DSACON32m controller.
SDH::cDSA is the end user interface class to access the DSACON32m, the tactile sensor controller of t...
cDSA(int debug_level=0, int port=1, char const *device_format_string="/dev/ttyS%d")
virtual void Close(void)=0
Close the previously opened communication channel.
void StoreNow(void)
Store current time internally.
#define USING_NAMESPACE_SDH
void ReadAndCheckErrorResponse(char const *msg, UInt8 command_id)
tCRCValue AddByte(unsigned char byte)
insert byte into CRC calculation and return the new current CRC checksum
#define DEFINE_TO_CASECOMMAND(_c)
void ReadMatrixInfo(sMatrixInfo *_matrix_info)
tTexel contact_force_cell_threshold
threshold of texel cell value for detecting forces with GetContactForce
const sMatrixInfo & GetMatrixInfo(int m) const
Return a reference to the sMatrixInfo of matrix m read from the remote DSACON32m controller.
#define NAMESPACE_SDH_END
bool acquiring_single_frame
flag, true if user requested acquiring of a single frame. Needed for DSACON32m firmware-bug workaroun...
void SetMatrixThreshold(int matrix_no, UInt16 threshold, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false)
tTexel GetTexel(int m, int x, int y) const
void SetFramerate(UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true)
@ eDSA_READ_DESCRIPTOR_STRING
eDSAPacketID
Command ID for the DSACON32m tactile sensor controller according to DSACON32_Command_Set_Reference_Ma...
void QueryControllerInfo(sControllerInfo *_controller_info)
tCRCValue GetCRC()
return the current CRC value
double Elapsed(void) const
Return time in seconds elapsed between the time stored in the object and now.
double VoltageToPressure(double voltage)
void QueryMatrixInfo(sMatrixInfo *_matrix_info, int matrix_no)
#define DSA_MAX_PREAMBLE_SEARCH
sSensitivityInfo GetMatrixSensitivity(int matrix_no)
int nb_cells
The total number of sensor cells.
static char const  * ErrorCodeToString(eDSAErrorCode error_code)
@ eDSA_SET_MATRIX_THRESHOLD
uint8_t UInt8
unsigned integer, size 1 Byte (8 Bit)
Derived exception class for low-level serial communication related exceptions.
@ E_FEATURE_NOT_SUPPORTED
void WriteCommand(UInt8 command)
void Init(int debug_level)
void QuerySensorInfo(sSensorInfo *_sensor_info)
double calib_voltage
see calib_pressure
UInt16 error_code
0000h, if successful, otherwise error code
void WriteCommandWithPayload(UInt8 command, UInt8 *payload, UInt16 payload_len)
@ eDSA_QUERY_SENSOR_CONFIGURATION
void Open(void)
(Re-)open connection to DSACON32m controller, this is called by the constructor automatically,...
Low-level communication class to access a serial port on Cygwin and Linux.
helper class to set value on construction and reset to previous value on destruction....
void QueryMatrixInfos(void)
@ eDSA_QUERY_MATRIX_CONFIGURATION
long read_timeout_us
default timeout used for reading in us
@ E_INSUFFICIENT_RESOURCES
sMatrixInfo * matrix_info
the matrix infos read from the remote DSACON32m controller
A data structure describing the sensor info about the remote DSACON32m controller.
uint16_t UInt16
unsigned integer, size 2 Byte (16 Bit)
Low-level communication class to access a CAN port.
@ eDSA_GET_PROPERTIES_CONTROL_VECTOR_OF_MATRIX
void ReadFrame(sTactileSensorFrame *frame_p)
double GetContactArea(int m)
@ eDSA_ADJUST_MATRIX_SENSITIVITY
void ReadControllerInfo(sControllerInfo *_controller_info)
A data structure describing the controller info about the remote DSACON32m controller.
UInt8 GetCRC_LB()
return the low byte of the current CRC value
Class for short, fixed maximum length text messages.
This file contains interface to #SDH::cDSA, a class to communicate with the tactile sensors of the SD...
sContactInfo GetContactInfo(int m)
sControllerInfo controller_info
the controller info read from the remote DSACON32m controller
Derived exception class for low-level DSA related exceptions.
@ eDSA_GET_MATRIX_THRESHOLD
std::ostream &NS_SDH operator<<(std::ostream &stream, cDSA::sControllerInfo const &controller_info)
void PDM(char const *fmt,...) SDH__attribute__((format(printf
sTactileSensorFrame frame
the latest frame received from the remote DSACON32m controller
void SetMatrixSensitivity(int matrix_no, double sensitivity, bool do_all_matrices=false, bool do_reset=false, bool do_persistent=false)
bool do_RLE
flag, true if data should be sent Run Length Encoded by the remote DSACON32m controller
UInt16 tTexel
data type for a single 'texel' (tactile sensor element)
@ eDSA_QUERY_CONTROLLER_STATE
#define NAMESPACE_SDH_START
virtual void Open(void)=0
Open rs232 port port.
struct VCC_EXPORT cDSA::sTactileSensorFrame SDH__attribute__
#define PRINT_MEMBER_HEX(_s, _var, _member)
unsigned long GetAgeOfFrame(sTactileSensorFrame *frame_p)
data structure for storing responses from the remote DSACON32m controller
void ParseFrame(sResponse *response, sTactileSensorFrame *frame_p)
void ReadSensorInfo(sSensorInfo *_sensor_info)
void FlushInput(long timeout_us_first, long timeout_us_subsequent)
void SetFramerateRetries(UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true, unsigned int retries=0, bool ignore_exceptions=false)
~cDSA()
Destructur: clean up and delete dynamically allocated memory.
const sSensorInfo & GetSensorInfo(void) const
Return a reference to the sSensorInfo read from the remote DSACON32m controller.
virtual ssize_t Read(void *data, ssize_t size, long timeout_us, bool return_on_less_data)=0
dummy class for (debug) stream output of bytes as list of hex values
@ eDSA_QUERY_CONTROLLER_CONFIGURATION
UInt16 GetMatrixThreshold(int matrix_no)
Structure to hold info about the sensitivity settings of one sensor patch.
tTexel contact_area_cell_threshold
threshold of texel cell value for detecting contacts with GetContactArea
const sTactileSensorFrame & GetFrame() const
return a reference to the latest tactile sensor frame without reading from remote DSACON32m
int * texel_offset
an array with the offsets of the first texel of all matrices into the whole frame
virtual int write(char const *ptr, int len=0)=0
Write data to a previously opened port.
UInt32 timestamp
the timestamp of the frame. Use GetAgeOfFrame() to set this into relation with the time of the PC.
This file contains settings to make the SDHLibrary compile on differen systems:
cDBG dbg
A stream object to print coloured debug messages.
UInt8 GetCRC_HB()
return the high byte of the current CRC value
USING_NAMESPACE_SDH NAMESPACE_SDH_START std::ostream * g_sdh_debug_log
#define PRINT_MEMBER(_s, _var, _member)
@ eDSA_SET_PROPERTIES_CONTROL_VECTOR_FOR_MATRIX
@ E_CMD_NOT_ENOUGH_PARAMS
uint32_t UInt32
unsigned integer, size 4 Byte (32 Bit)
A data structure describing a full tactile sensor frame read from the remote DSACON32m controller.
Interface of class #SDH::cSDHBase.
virtual const char * what() const
cDBG dbg
A stream object to print colored debug messages.
@ eDSA_CONFIGURE_DATA_ACQUISITION
double force_factor
additional calibration factor for forces in GetContactForce
cSerialBase * com
the communication interface to use
Interface of auxilliary utility functions for SDHLibrary-CPP.
void Close(void)
Set the framerate of the remote DSACON32m controller to 0 and close connection to it.
void ReadResponse(sResponse *response, UInt8 command_id)
@ eDSA_QUERY_CONTROLLER_FEATURES
A derived CRC class that uses a CRC table and initial value suitable for the Weiss Robotics DSACON32m...
tTexel * texel
an 2D array of tTexel elements. Use GetTexel() for easy access to specific individual elements.
Interface of class #SDH::cTCPSerial, class to access TCP port cygwin/linux.
sSensorInfo sensor_info
the sensor info read from the remote DSACON32m controller
eDSAErrorCode
error codes returned by the remote DSACON32m tactile sensor controller
sdhlibrary_cpp
Author(s): Dirk Osswald 
autogenerated on Wed Mar 2 2022 01:00:58