SVHFingerManager.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // This file is part of the SCHUNK SVH Driver suite.
5 //
6 // This program is free software licensed under the LGPL
7 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
8 // You can find a copy of this license in LICENSE folder in the top
9 // directory of the source code.
10 //
11 // © Copyright 2014 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
12 // © Copyright 2014 FZI Forschungszentrum Informatik, Karlsruhe, Germany
13 //
14 // -- END LICENSE BLOCK ------------------------------------------------
15 
16 //----------------------------------------------------------------------
29 //----------------------------------------------------------------------
30 #ifndef DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
31 #define DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
32 
39 
40 #include <boost/shared_ptr.hpp>
41 
42 
43 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
44 #include <icl_comm_websocket/WsBroadcaster.h>
45 #else
46 // Forward Deklaration of the WsBroadcaster
47 // This is not needed for normal driver operation
48 // but might be added later. To keep the interface the same
49 // a forward declaration becomes necessary
50 namespace icl_comm{
51 namespace websocket{
52  class WsBroadcaster;
53 }}// NS end
54 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
55 
56 
57 
58 
59 namespace driver_svh {
60 
64 {
65 public:
66 
71  {
78  eST_DIMENSION
79  };
80 
84  enum Hints
85  {
86  eHT_DEVICE_NOT_FOUND, /* ttyUSBx could not be found */
87  eHT_CONNECTION_FAILED, /* ttyUSB could be opened but communication failed */
88  eHT_NOT_RESETTED, /* the fingers of the hand are not resetted */
89  eHT_NOT_CONNECTED, /* simply never called connect */
90  eHT_RESET_FAILED, /* timeout during reset -> this is a serious failure */
91  eHT_CHANNEL_SWITCHED_OF,/* Not realy a problem, however a hint worth noting */
92  eHT_DANGEROUS_CURRENTS, /* Current Values are set to dangerous levels */
93  eHT_DIMENSION /* dummy entry indicating the size, not used as status */
94  };
95 
100  SVHFingerManager(const std::vector<bool> &disable_mask = std::vector<bool>(9,false), const uint32_t &reset_timeout = 5);
101 
102  virtual ~SVHFingerManager();
103 
110  bool connect(const std::string &dev_name = "/dev/ttyUSB0",const unsigned int &_retry_count = 3);
111 
115  void disconnect();
116 
121  bool isConnected() { return m_connected; }
122 
128  bool resetChannel(const SVHChannel &channel);
129 
135  bool enableChannel(const SVHChannel &channel);
136 
141  void disableChannel(const SVHChannel &channel);
142 
147  bool requestControllerFeedbackAllChannels();
148 
154  bool requestControllerFeedback(const SVHChannel &channel);
155 
162  bool getPosition(const SVHChannel &channel, double &position);
163 
170  bool getCurrent(const SVHChannel &channel, double &current);
171 
172 
178  bool setAllTargetPositions(const std::vector<double>& positions);
179 
187  bool setTargetPosition(const SVHChannel &channel, double position, double current);
188 
194  bool isEnabled(const SVHChannel &channel);
195 
201  bool isHomed(const SVHChannel &channel);
202 
208  void setMovementState(const MovementState &state);
209 
210 
213  void requestControllerState();
214 
221  bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings);
222 
229  bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings);
230 
231 
238  bool setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings);
239 
246  bool setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings);
247 
254  bool setHomeSettings(const SVHChannel &channel,const SVHHomeSettings& home_settings);
255 
256 
257 
258  // These 3 functions could be private but where made public for printing and debug purposes. As there is no harm to it it should not be a problem
259 
261  std::vector<SVHCurrentSettings> getDefaultCurrentSettings();
262 
265  std::vector<SVHPositionSettings> getDefaultPositionSettings(const bool& reset = false);
266 
268  void setDefaultHomeSettings();
269 
274  void setResetSpeed(const float& speed);
275 
280  void setResetTimeout(const int& resetTimeout);
281 
286  SVHFirmwareInfo getFirmwareInfo();
287 
288 
289  #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
290 
296  void updateWebSocket();
297 
302  void receivedHintMessage(const int &hint);
303 
304  #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
305 
306 // ----------------------------------------------------------------------
307 // ---- private functions and varaibles
308 // ----------------------------------------------------------------------
309 
310 private:
311 
314 
317 
320 
323 
326 
329 
331  std::vector<double> m_ticks2rad;
332 
334  std::vector<int32_t> m_position_min;
335 
337  std::vector<int32_t> m_position_max;
338 
340  std::vector<int32_t> m_position_home;
341 
343  std::vector<bool> m_is_homed;
344 
346  std::vector<bool> m_is_switched_off;
347 
350 
353 
356 
358  std::vector<SVHCurrentSettings> m_current_settings;
360  std::vector<bool> m_current_settings_given;
361 
363  std::vector<SVHPositionSettings> m_position_settings;
365  std::vector<bool> m_position_settings_given;
366 
368  std::vector<SVHHomeSettings> m_home_settings;
369 
373  std::string m_serial_device;
374 
376  std::vector<SVHChannel> m_reset_order;
377 
384  std::vector<double> m_reset_current_factor;
385 
392  int32_t convertRad2Ticks(const SVHChannel &channel,const double &position);
393 
400  double convertTicks2Rad(const SVHChannel &channel, const int32_t &ticks);
401 
408  bool isInsideBounds(const SVHChannel &channel, const int32_t &target_position);
409 
416  bool currentSettingsAreSafe(const SVHChannel &channel,const SVHCurrentSettings &current_settings);
417 
418  // DEBUG
420 
421 
422 };
423 
424 }
425 
426 #endif
std::vector< SVHChannel > m_reset_order
vector storing the reset order of the channels
float m_reset_speed_factor
Factor for determining the finger speed during reset. Only 0.0-1.0 is allowed.
std::vector< bool > m_is_homed
vector storing reset flags for each channel
std::vector< bool > m_position_settings_given
Information about the validity of externaly given values for the position settings (easier to use thi...
signed int int32_t
unsigned int uint32_t
MovementState
The MovementState enum indicated the overall state of the hand. Currently only used for updating the ...
std::vector< SVHCurrentSettings > m_current_settings
Vector of current controller parameters for each finger (as given by external config) ...
SVHFeedbackPollingThread * m_feedback_thread
pointer to svh controller
std::vector< int32_t > m_position_max
max position vector for each channel
std::vector< double > m_ticks2rad
position conversion factor (ticks to RAD) for each channel
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
Websocket handle for updating diagnostic backend (OPTIONAL)
signed char int8_t
The SVHCurrentSettings save the current controller paramters for a single motor.
#define DRIVER_SVH_IMPORT_EXPORT
Definition: ImportExport.h:43
int8_t m_homing_timeout
vector storing reset flags for each finger
bool m_connection_feedback_given
Helper variable to check if feedback was printed (will be replaced by a better solution in the future...
bool isConnected()
returns connected state of finger manager
std::string m_serial_device
m_serial_device Device handle of the device to use, is overwritten if connect is called with an argum...
MovementState m_movement_state
Overall movement State to indicate what the hand is doing at the moment.
std::vector< int32_t > m_position_min
min position vector for each channel
std::vector< SVHHomeSettings > m_home_settings
Vector of home settings for each finger (as given by external config)
Hints
The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface.
std::vector< SVHPositionSettings > m_position_settings
Vector of position controller parameters for each finger (as given by external config) ...
std::vector< int32_t > m_position_home
home position after complete reset of each channel
The SVHFirmwareInfo holds the data of a firmware response from the hardware.
The SVHControllerFeedback saves the feedback of a single motor.
std::vector< bool > m_is_switched_off
vector storing information if a finger is enabled. In Case it is all request for it will be granted b...
uint32_t m_reset_timeout
Time in seconds after which the a reset is aborted if no change in current is observable.
bool m_connected
holds the connected state
std::vector< double > m_reset_current_factor
Vector containing factors for the currents at reset. Vector containing factors for the currents at re...
This class controls the the SCHUNK five finger hand.
Definition: SVHController.h:77
Thread for periodically requesting feedback messages from the SCHUNK five finger hand.
The SVHPositionSettings save the position controller paramters for a single motor.
SVHControllerFeedback debug_feedback
data sctructure for home positions
std::vector< bool > m_current_settings_given
Information about the validity of externaly given values for the current settings (easier to use this...
SVHChannel
Channel indicates which motor to use in command calls. WARNING: DO NOT CHANGE THE ORDER OF THESE as i...
Definition: SVHController.h:56
SVHController * m_controller
pointer to svh controller


schunk_svh_driver
Author(s): Georg Heppner
autogenerated on Mon Jun 10 2019 15:04:59