dsa.h
Go to the documentation of this file.
1 //======================================================================
27 //======================================================================
28 
29 #ifndef DSA_h_
30 #define DSA_h_
31 
32 #include "sdhlibrary_settings.h"
33 
34 //----------------------------------------------------------------------
35 // System Includes - include with <>
36 //----------------------------------------------------------------------
37 
38 #include <assert.h>
39 
40 //----------------------------------------------------------------------
41 // Project Includes - include with ""
42 //----------------------------------------------------------------------
43 
44 #include "sdhexception.h"
45 
46 #include "dbg.h"
47 #if SDH_USE_VCC
48 # include "rs232-vcc.h"
49 #else
50 # include "rs232-cygwin.h"
51 #endif
52 #include "simpletime.h"
53 #include "crc.h"
54 
55 //----------------------------------------------------------------------
56 // Defines, enums, unions, structs
57 //----------------------------------------------------------------------
58 
60 
61 #define DSA_MAX_PREAMBLE_SEARCH (2*3*(6*(14+13)) + 16)
62 
63 //----------------------------------------------------------------------
64 // Global variables (declarations)
65 //----------------------------------------------------------------------
66 
67 
68 //----------------------------------------------------------------------
69 // External functions (function declarations)
70 //----------------------------------------------------------------------
71 
72 
73 //----------------------------------------------------------------------
74 // Function prototypes (function declarations)
75 //----------------------------------------------------------------------
76 
77 
78 //----------------------------------------------------------------------
79 // Class declarations
80 //----------------------------------------------------------------------
81 
82 
83 
84 
88 class VCC_EXPORT cDSAException: public cSDHLibraryException
89 {
90 public:
91  cDSAException( cMsg const & _msg )
92  : cSDHLibraryException( "cDSAException", _msg )
93  {}
94 };
95 //======================================================================
96 
98 
111 class VCC_EXPORT cDSA
112 {
113  public:
115  typedef UInt16 tTexel;
118  enum eDSAErrorCode
119  {
120  E_SUCCESS,
121  E_NOT_AVAILABLE,
122  E_NO_SENSOR,
123  E_NOT_INITIALIZED,
124  E_ALREADY_RUNNING,
125  E_FEATURE_NOT_SUPPORTED,
126  E_INCONSISTENT_DATA,
127  E_TIMEOUT,
129  E_WRITE_ERROR,
130  E_INSUFFICIENT_RESOURCES,
131  E_CHECKSUM_ERROR,
132  E_CMD_NOT_ENOUGH_PARAMS,
147  E_RANGE_ERROR
148  };
149 
150 
152 #if SDH_USE_VCC
153 #pragma pack(push,1) // for VCC (MS Visual Studio) we have to set the necessary 1 byte packing with this pragma
154 #endif
156  {
167  } SDH__attribute__((__packed__)); // for gcc we have to set the necessary 1 byte packing with this attribute
168 
170  struct sSensorInfo
171  {
178  } SDH__attribute__((__packed__)); // for gcc we have to set the necessary 1 byte packing with this attribute
179 
181  struct sMatrixInfo
182  {
184  float texel_width;
188  UInt8 uid[6];
191 
195 
199  float fullscale;
201  } SDH__attribute__((__packed__)); // for gcc we have to set the necessary 1 byte packing with this attribute
202 
205  {
208  float cur_sens;
212  float fact_sens;
214  } SDH__attribute__((__packed__)); // for gcc we have to set the necessary 1 byte packing with this attribute
217 
218 #if SDH_USE_VCC
219 #pragma pack(pop) // for VCC (MS Visual Studio) restore normal packing
220 #endif
221 
222 
235  struct VCC_EXPORT sTactileSensorFrame
236  {
239  tTexel* texel;
240 
243  {
244  texel = NULL;
245  }
246  };
247 
250  {
251  double force;
252  double area;
253  double cog_x;
254  double cog_y;
255  };
256 
269  protected:
272 #if SDH_USE_VCC
273 #pragma pack(push,1) // for VCC (MS Visual Studio) we have to set the necessary 1 byte packing with this pragma
274 #endif
275  struct sResponse {
280 
282  sResponse( UInt8* _payload, int _max_payload_size )
283  {
284  payload = _payload;
285  max_payload_size = _max_payload_size;
286  }
287  } SDH__attribute__((__packed__)); // for gcc we have to set the necessary 1 byte packing with this attribute
288 #if SDH_USE_VCC
289 #pragma pack(pop) // for VCC (MS Visual Studio) restore normal packing
290 #endif
291 
292  friend VCC_EXPORT std::ostream &operator<<(std::ostream &stream, cDSA::sResponse const &response );
293 
296 
299 
301  bool do_RLE;
302 
305 
308 
311 
314 
316  int nb_cells;
317 
320 
323 
326 
329 
332 
334  double force_factor;
335 
336 
340  double calib_pressure; // N/(mm*mm)
342  double calib_voltage; // "what the DSA reports:" ~mV
343 
344 
345  void WriteCommandWithPayload( UInt8 command, UInt8* payload, UInt16 payload_len );
346 
347  inline void WriteCommand( UInt8 command )
348  {
349  WriteCommandWithPayload( command, NULL, 0 );
350  }
351  //----------------------------------------------------------------------
352 
363  void ReadResponse( sResponse* response, UInt8 command_id );
364 
368  void ReadControllerInfo( sControllerInfo* _controller_info );
369 
370 
374  void ReadSensorInfo( sSensorInfo* _sensor_info );
375 
376 
380  void ReadMatrixInfo( sMatrixInfo* _matrix_info );
381 
382 
386  void ReadFrame( sTactileSensorFrame* frame_p );
387 
388 
393  void QueryControllerInfo( sControllerInfo* _controller_info );
394 
395 
400  void QuerySensorInfo( sSensorInfo* _sensor_info );
401 
402 
407  void QueryMatrixInfo( sMatrixInfo* _matrix_info, int matrix_no );
408 
409 
413  void QueryMatrixInfos( void );
414 
415 
419  void ParseFrame( sResponse* response, sTactileSensorFrame* frame_p );
420 
421 
422  public:
442  cDSA( int debug_level=0, int port=1, char const* device_format_string="/dev/ttyS%d" );
443 
463  cDSA( int debug_level, char const* _tcp_adr, int _tcp_port=13000, double _timeout=1.0 );
464 
465 
467  ~cDSA();
468 
469 
471  inline sControllerInfo const & GetControllerInfo( void ) const
472  {
473  return controller_info;
474  }
475  //-----------------------------------------------------------------
476 
478  inline sSensorInfo const & GetSensorInfo( void ) const
479  {
480  return sensor_info;
481  }
482  //-----------------------------------------------------------------
483 
485  inline sMatrixInfo const & GetMatrixInfo( int m ) const
486  {
487  assert( 0 <= m && m <= (int ) sensor_info.nb_matrices );
488  return matrix_info[m];
489  }
490  //-----------------------------------------------------------------
491 
493  inline sTactileSensorFrame const & GetFrame() const
494  {
495  return frame;
496  }
497  //-----------------------------------------------------------------
498 
501  {
502  ReadFrame( &frame );
503  return frame;
504  }
505  //-----------------------------------------------------------------
506 
508  void Open(void);
509 
511  void Close(void);
512 
513 
542  void SetFramerate( UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true );
543 
556  void SetFramerateRetries( UInt16 framerate, bool do_RLE=true, bool do_data_acquisition=true, unsigned int retries=0, bool ignore_exceptions=false );
557 
558 
573  sSensitivityInfo GetMatrixSensitivity( int matrix_no );
574 
575 
592  void SetMatrixSensitivity( int matrix_no,
593  double sensitivity,
594  bool do_all_matrices=false,
595  bool do_reset=false,
596  bool do_persistent=false );
597 
598 
615  void SetMatrixThreshold( int matrix_no,
616  UInt16 threshold,
617  bool do_all_matrices=false,
618  bool do_reset=false,
619  bool do_persistent=false );
620 
630  UInt16 GetMatrixThreshold( int matrix_no );
631 
635  tTexel GetTexel( int m, int x, int y ) const;
636 
637 
638 
642  inline int GetMatrixIndex( int fi, int part )
643  {
644  return fi * 2 + part;
645  }
646 
647 
651  inline unsigned long GetAgeOfFrame( sTactileSensorFrame* frame_p )
652  {
653  return ((unsigned long) (start_pc.Elapsed()*1000.0)) - (frame_p->timestamp - start_dsa);
654  }
655 
656  double GetContactArea( int m );
657 
658  private:
659  double VoltageToPressure( double voltage );
660 
661  void ReadAndCheckErrorResponse( char const* msg, UInt8 command_id );
662 
666  void Init( int debug_level );
667 
668 
669  public:
670  sContactInfo GetContactInfo( int m );
671 
672 
679  static char const* ErrorCodeToString( eDSAErrorCode error_code );
680  static char const* ErrorCodeToString( UInt16 error_code )
681  {
682  return ErrorCodeToString( (eDSAErrorCode) error_code );
683  }
684 
685  private:
688 
700  void FlushInput( long timeout_us_first, long timeout_us_subsequent );
701 }; // end of class cDSA
702 //----------------------------------------------------------------------
703 //----------------------------------------------------------------------
704 
705 
706 VCC_EXPORT std::ostream &operator<<( std::ostream &stream, cDSA::sControllerInfo const &controller_info );
707 
708 
709 VCC_EXPORT std::ostream &operator<<( std::ostream &stream, cDSA::sSensorInfo const &sensor_info );
710 
711 
712 VCC_EXPORT std::ostream &operator<<( std::ostream &stream, cDSA::sMatrixInfo const &matrix_info );
713 
714 
715 VCC_EXPORT std::ostream &operator<<( std::ostream &stream, cDSA::sResponse const &response );
716 
717 
718 VCC_EXPORT std::ostream &operator<<( std::ostream &stream, cDSA const &dsa );
719 
720 
722 
723 #endif
724 
725 
726 //======================================================================
727 /*
728 {
729  Here are some settings for the emacs/xemacs editor (and can be safely ignored):
730  (e.g. to explicitely set C++ mode for *.h header files)
731 
732  Local Variables:
733  mode:C
734  mode:ELSE
735  End:
736 }
737 */
738 //======================================================================}
Structure to hold info about the contact of one sensor patch.
Definition: dsa.h:249
cDBG dbg
A stream object to print coloured debug messages.
Definition: dsa.h:295
double calib_voltage
see calib_pressure
Definition: dsa.h:342
double force_factor
additional calibration factor for forces in GetContactForce
Definition: dsa.h:334
Interface of auxilliary utility functions for SDHLibrary-CPP.
VCC_EXPORT std::ostream & operator<<(std::ostream &stream, cDSA::sControllerInfo const &controller_info)
Definition: dsa.cpp:1121
UInt32 timestamp
the timestamp of the frame. Use GetAgeOfFrame() to set this into relation with the time of the PC...
Definition: dsa.h:237
A class to print colored debug messages.
Definition: dbg.h:113
sMatrixInfo const & GetMatrixInfo(int m) const
Return a reference to the sMatrixInfo of matrix m read from the remote DSACON32m controller.
Definition: dsa.h:485
UInt16 cells_x
Definition: dsa.h:186
uint8_t UInt8
unsigned integer, size 1 Byte (8 Bit)
Definition: basisdef.h:61
UInt8 senscon_type
Definition: dsa.h:163
cSerialBase * com
the communication interface to use
Definition: dsa.h:298
UInt16 cells_y
Definition: dsa.h:187
sResponse(UInt8 *_payload, int _max_payload_size)
constructor to init pointer and max size
Definition: dsa.h:282
float fact_sens
Definition: dsa.h:123
UInt8 feature_flags
Definition: dsa.h:162
UInt8 hw_revision
Definition: dsa.h:190
#define NULL
Definition: getopt1.c:56
tTexel contact_force_cell_threshold
threshold of texel cell value for detecting forces with GetContactForce
Definition: dsa.h:331
sTactileSensorFrame frame
the latest frame received from the remote DSACON32m controller
Definition: dsa.h:313
UInt8 packet_id
Definition: dsa.h:276
Derived exception class for low-level DSA related exceptions.
Definition: dsa.h:88
long read_timeout_us
default timeout used for reading in us
Definition: dsa.h:322
static char const * ErrorCodeToString(UInt16 error_code)
Definition: dsa.h:680
UInt16 error_code
Definition: dsa.h:183
double Elapsed(void) const
Return time in seconds elapsed between the time stored in the object and now.
Definition: simpletime.h:115
UInt16 error_code
0000h, if successful, otherwise error code
Definition: dsa.h:116
float matrix_theta_z
Definition: dsa.h:198
This file contains interface to cCRC, a class to handle CRC calculation.
UInt32 serial_no
Definition: dsa.h:158
int GetMatrixIndex(int fi, int part)
Definition: dsa.h:642
UInt8 hw_revision
Definition: dsa.h:175
UInt16 tTexel
data type for a single &#39;texel&#39; (tactile sensor element)
Definition: dsa.h:115
double force
accumulated force in N
Definition: dsa.h:251
eDSAErrorCode
error codes returned by the remote DSACON32m tactile sensor controller
Definition: dsa.h:118
UInt16 error_code
Definition: dsa.h:157
This file contains interface and implementation of class #SDH::cDBG, a class for colorfull debug mess...
UInt8 flags
internal data
Definition: dsa.h:238
UInt32 start_dsa
Definition: dsa.h:325
Interface of the exception base class #SDH::cSDHLibraryException and #SDH::cMsg.
UInt8 * payload
Definition: dsa.h:270
float matrix_center_x
Definition: dsa.h:192
uint32_t UInt32
unsigned integer, size 4 Byte (32 Bit)
Definition: basisdef.h:65
Low-level communication class to access a serial port.
Definition: serialbase.h:105
cSimpleTime start_pc
Definition: dsa.h:324
#define NAMESPACE_SDH_START
UInt16 error_code
Definition: dsa.h:172
float matrix_theta_y
Definition: dsa.h:197
UInt8 active_interface
Definition: dsa.h:164
SDH::cDSA is the end user interface class to access the DSACON32m, the tactile sensor controller of t...
Definition: dsa.h:111
Base class for exceptions in the SDHLibrary-CPP.
Definition: sdhexception.h:132
float texel_width
Definition: dsa.h:184
tTexel contact_area_cell_threshold
threshold of texel cell value for detecting contacts with GetContactArea
Definition: dsa.h:328
data structure for storing responses from the remote DSACON32m controller
Definition: dsa.h:275
float fullscale
Definition: dsa.h:199
float matrix_center_z
Definition: dsa.h:194
UInt16 error_code
0000h, if successful, otherwise error code
Definition: dsa.h:206
Int32 max_payload_size
Definition: dsa.h:279
cDSAException(cMsg const &_msg)
Definition: dsa.h:91
UInt8 feature_flags
Definition: dsa.h:200
UInt8 feature_flags
Definition: dsa.h:177
sTactileSensorFrame(void)
constructor
Definition: dsa.h:242
A data structure describing the sensor info about the remote DSACON32m controller.
Definition: dsa.h:170
sSensorInfo sensor_info
the sensor info read from the remote DSACON32m controller
Definition: dsa.h:307
int * texel_offset
an array with the offsets of the first texel of all matrices into the whole frame ...
Definition: dsa.h:319
UInt16 nb_matrices
Definition: dsa.h:173
bool acquiring_single_frame
flag, true if user requested acquiring of a single frame. Needed for DSACON32m firmware-bug workaroun...
Definition: dsa.h:687
double calib_pressure
Definition: dsa.h:340
tTexel * texel
an 2D array of tTexel elements. Use GetTexel() for easy access to specific individual elements...
Definition: dsa.h:239
float texel_height
Definition: dsa.h:185
UInt16 sw_version
Definition: dsa.h:160
bool m_read_another
Definition: dsa.h:267
sTactileSensorFrame const & GetFrame() const
return a reference to the latest tactile sensor frame without reading from remote DSACON32m ...
Definition: dsa.h:493
Interface of class #SDH::cRS232, a class to access serial RS232 port on cygwin/linux.
UInt8 * payload
Definition: dsa.h:278
Structure to hold info about the sensitivity settings of one sensor patch.
Definition: dsa.h:204
#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 ...
Definition: dsa.h:301
This file contains settings to make the SDHLibrary compile on differen systems:
float matrix_theta_x
Definition: dsa.h:196
Very simple class to measure elapsed time.
Definition: simpletime.h:84
float matrix_center_y
Definition: dsa.h:193
UInt8 status_flags
Definition: dsa.h:161
sControllerInfo controller_info
the controller info read from the remote DSACON32m controller
Definition: dsa.h:304
UInt8 uid[6]
Definition: dsa.h:121
A data structure describing a full tactile sensor frame read from the remote DSACON32m controller...
Definition: dsa.h:235
float cur_sens
Definition: dsa.h:121
UInt16 generated_by
Definition: dsa.h:174
UInt32 can_baudrate
Definition: dsa.h:165
double cog_y
center of gravity of contact in y direction of sensor patch in mm
Definition: dsa.h:254
sMatrixInfo * matrix_info
the matrix infos read from the remote DSACON32m controller
Definition: dsa.h:310
sSensorInfo const & GetSensorInfo(void) const
Return a reference to the sSensorInfo read from the remote DSACON32m controller.
Definition: dsa.h:478
Class for short, fixed maximum length text messages.
Definition: sdhexception.h:77
double area
area of contact in mm*mm.
Definition: dsa.h:252
sTactileSensorFrame const & UpdateFrame()
read the tactile sensor frame from remote DSACON32m and return a reference to it. A command to query ...
Definition: dsa.h:500
sControllerInfo const & GetControllerInfo(void) const
Return a reference to the sControllerInfo read from the remote DSACON32m controller.
Definition: dsa.h:471
UInt8 reserved[2]
Definition: dsa.h:122
Implementation of class #SDH::cRS232, a class to access serial RS232 port with VCC compiler on Window...
unsigned long GetAgeOfFrame(sTactileSensorFrame *frame_p)
Definition: dsa.h:651
int32_t Int32
signed integer, size 4 Byte (32 Bit)
Definition: basisdef.h:64
void WriteCommand(UInt8 command)
Definition: dsa.h:347
UInt16 size
Definition: dsa.h:277
A data structure describing a single sensor matrix connected to the remote DSACON32m controller...
Definition: dsa.h:181
UInt32 serial_no
Definition: dsa.h:176
uint16_t UInt16
unsigned integer, size 2 Byte (16 Bit)
Definition: basisdef.h:63
double cog_x
center of gravity of contact in x direction of sensor patch in mm
Definition: dsa.h:253
UInt8 hw_version
Definition: dsa.h:159
int nb_cells
The total number of sensor cells.
Definition: dsa.h:316
A data structure describing the controller info about the remote DSACON32m controller.
Definition: dsa.h:155


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