SVHFingerManager.cpp
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 //----------------------------------------------------------------------
32 //----------------------------------------------------------------------
33 #include <driver_svh/Logging.h>
35 
36 #include <icl_core/TimeStamp.h>
37 
38 #include <boost/bind/bind.hpp>
39 
40 namespace driver_svh {
41 
42 SVHFingerManager::SVHFingerManager(const std::vector<bool> &disable_mask, const uint32_t &reset_timeout) :
43  m_controller(new SVHController()),
44  m_feedback_thread(),
45  m_connected(false),
46  m_connection_feedback_given(false),
47  m_homing_timeout(10),
48  m_ticks2rad(0),
49  m_position_min(eSVH_DIMENSION, 0),
50  m_position_max(eSVH_DIMENSION, 0),
51  m_position_home(eSVH_DIMENSION, 0),
52  m_is_homed(eSVH_DIMENSION, false),
53  m_is_switched_off(eSVH_DIMENSION,false),
54  m_movement_state(eST_DEACTIVATED),
55  m_reset_speed_factor(0.2),
56  m_reset_timeout(reset_timeout),
57  m_current_settings(eSVH_DIMENSION),
58  m_current_settings_given(eSVH_DIMENSION,false),
59  m_position_settings(eSVH_DIMENSION),
60  m_position_settings_given(eSVH_DIMENSION,false),
61  m_home_settings(eSVH_DIMENSION),
62  m_serial_device("/dev/ttyUSB0")
63 {
64 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
65  m_ws_broadcaster = boost::shared_ptr<icl_comm::websocket::WsBroadcaster>(new icl_comm::websocket::WsBroadcaster(icl_comm::websocket::WsBroadcaster::eRT_SVH));
66  if (m_ws_broadcaster)
67  {
68  // Register a custom handler for received JSON Messages
69  m_ws_broadcaster->registerHintCallback(boost::bind(&SVHFingerManager::receivedHintMessage,this,_1));
70 
71  m_ws_broadcaster->robot->setInputToRadFactor(1);
72  m_ws_broadcaster->robot->setHint(eHT_NOT_CONNECTED);
73  m_ws_broadcaster->sendHints(); // Hints are updated Manually
74  m_ws_broadcaster->sendState(); // Initial send in case someone is waiting for it
75  }
76 #endif
77 
78 
79  // load home position default parameters
81 
82  // set default reset order of all channels
93 
94  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
95  {
96  m_is_switched_off[i] = disable_mask[i];
97  if (m_is_switched_off[i])
98  {
99  LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Joint: " << m_controller->m_channel_description[i] << " was disabled as per user request. It will not do anything!" << endl);
100 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
101  if (m_ws_broadcaster)
102  {
103  m_ws_broadcaster->robot->setHint(eHT_CHANNEL_SWITCHED_OF);
104  m_ws_broadcaster->sendHints(); // Hints are updated Manually
105  }
106 #endif
107  }
108  }
109 
110 
111 }
112 
114 {
115  if (m_connected)
116  {
117  disconnect();
118  }
119 
120  if (m_controller != NULL)
121  {
122  delete m_controller;
123  m_controller = NULL;
124  }
125 }
126 
127 bool SVHFingerManager::connect(const std::string &dev_name,const unsigned int &_retry_count)
128 {
129  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Finger manager is trying to connect to the Hardware..." << endl);
130 
131 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
132  // Reset the connection specific hints and give it a go aggain.
133  if (m_ws_broadcaster)
134  {
135  m_ws_broadcaster->robot->clearHint(eHT_NOT_CONNECTED);
136  m_ws_broadcaster->robot->clearHint(eHT_DEVICE_NOT_FOUND);
137  m_ws_broadcaster->robot->clearHint(eHT_CONNECTION_FAILED);
138  m_ws_broadcaster->sendHints(); // Hints are updated Manually
139  }
140 #endif
141 
142  // Save device handle for next use
143  m_serial_device = dev_name;
144 
145 
146  if (m_connected)
147  {
148  disconnect();
149  }
150 
151  if (m_controller != NULL)
152  {
153  if (m_controller->connect(dev_name))
154  {
155  unsigned int retry_count=_retry_count;
156  do {
157  // Reset the package counts (in case a previous attempt was made)
159 
160  // initialize feedback polling thread
162 
163  // load default position settings before the fingers are resetted
164  std::vector<SVHPositionSettings> position_settings = getDefaultPositionSettings(true);
165 
166  // load default current settings
167  std::vector<SVHCurrentSettings> current_settings
169 
171 
172  // initialize all channels
173  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
174  {
175  // request controller feedback to have a valid starting point
176  m_controller->requestControllerFeedback(static_cast<SVHChannel>(i));
177 
178  // Actually set the new position settings
179  m_controller->setPositionSettings(static_cast<SVHChannel>(i), position_settings[i]);
180 
181  // set current settings
182  m_controller->setCurrentSettings(static_cast<SVHChannel>(i), current_settings[i]);
183  }
184 
185  // check for correct response from hardware controller
187  bool timeout = false;
188  unsigned int received_count = 0;
189  unsigned int send_count = 0;
190  while (!timeout && !m_connected)
191  {
192  send_count = m_controller->getSentPackageCount();
193  received_count = m_controller->getReceivedPackageCount();
194  if (send_count == received_count)
195  {
196  m_connected = true;
197  LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Successfully established connection to SCHUNK five finger hand." << endl
198  << "Send packages = " << send_count << ", received packages = " << received_count << endl);
199 
200  }
201  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Try to connect to SCHUNK five finger hand: Send packages = " << send_count << ", received packages = " << received_count << endl);
202 
203  // check for timeout
204  if ((icl_core::TimeStamp::now() - start_time).tsSec() > m_reset_timeout)
205  {
206  timeout = true;
207  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Connection timeout! Could not connect to SCHUNK five finger hand." << endl
208  << "Send packages = " << send_count << ", received packages = " << received_count << endl);
209 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
210  if (m_ws_broadcaster)
211  {
212  m_ws_broadcaster->robot->setHint(eHT_CONNECTION_FAILED);
213  m_ws_broadcaster->sendHints(); //Hints are updated Manually
214  }
215 #endif
216 
217  }
218  icl_core::os::usleep(50000);
219  }
220 
221  // Try Aggain, but ONLY if we at least got one package back, otherwise its futil
222  if (!m_connected)
223  {
224  if (received_count > 0 && retry_count >= 0)
225  {
226  retry_count--;
227  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Connection Failed! Send packages = " << send_count << ", received packages = " << received_count << ". Retrying, count: " << retry_count << endl);
228  }
229  else
230  {
231  retry_count = 0;
232  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Connection Failed! Send packages = " << send_count << ", received packages = " << received_count << ". Not Retrying anymore."<< endl);
233  }
234  }
235  // Keep trying to reconnect several times because the brainbox often makes problems
236  } while (!m_connected && retry_count > 0);
237 
238 
239  if (!m_connected && retry_count<= 0)
240  {
241  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "A Stable connection could NOT be made, however some packages where received. Please check the hardware!" << endl);
242  }
243 
244 
245  if (m_connected)
246  {
247 
248 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
249 
250  if (m_ws_broadcaster)
251  {
252  // Intitial connection, any failures regarding the connection must be gone so we can safely clear them all
253  m_ws_broadcaster->robot->clearHint(eHT_CONNECTION_FAILED);
254  m_ws_broadcaster->robot->clearHint(eHT_NOT_CONNECTED);
255  m_ws_broadcaster->robot->clearHint(eHT_DEVICE_NOT_FOUND);
256  // Next up, resetting, so give a hint for that
257  m_ws_broadcaster->robot->setHint(eHT_NOT_RESETTED);
258  m_ws_broadcaster->sendHints(); // Needs to be called if not done by the feedback polling thread
259  }
260 #endif
261 
262  // Request firmware information once at the beginning
263  getFirmwareInfo();
264  // start feedback polling thread
265  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Finger manager is starting the fedback polling thread" << endl);
266  if (m_feedback_thread != NULL)
267  {
269  }
270  }
271  }
272  else
273  {
274 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
275  if (m_ws_broadcaster)
276  {
277  m_ws_broadcaster->robot->setHint(eHT_DEVICE_NOT_FOUND);
278  m_ws_broadcaster->sendHints(); // Hints are updated Manually
279  }
280 #endif
281  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Connection FAILED! Device could NOT be opened" << endl);
282  }
283  }
284 
285  return m_connected;
286 }
287 
289 {
290  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Finger manager is trying to discoconnect to the Hardware..." << endl);
291  m_connected = false;
293 
294  // Disable Polling
295  if (m_feedback_thread != NULL)
296  {
297  // wait until thread has stopped
300 
301  delete m_feedback_thread;
302  m_feedback_thread = NULL;
303  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Feedback thread terminated" << endl);
304  }
305 
306  // Tell the Controller to terminate the rest
307  if (m_controller != NULL)
308  {
310  }
311 
312 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
313  // Connection hint is always true when no connection is established :)
314  if (m_ws_broadcaster)
315  {
316  m_ws_broadcaster->robot->clearAllHints();
317  m_ws_broadcaster->robot->setHint(eHT_NOT_CONNECTED);
318  m_ws_broadcaster->sendHints(); // Hints are Transmitted Manually
319  }
320 #endif
321 
322 }
323 
326 {
327  if (m_connected)
328  {
329  // reset all channels
330  if (channel == eSVH_ALL)
331  {
332 
333  bool reset_all_success = true;
334  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
335  {
336  // try three times to reset each finger
337  size_t max_reset_counter = 3;
338  bool reset_success = false;
339  while (!reset_success && max_reset_counter > 0)
340  {
341  SVHChannel channel = static_cast<SVHChannel>(m_reset_order[i]);
342  reset_success = resetChannel(channel);
343  max_reset_counter--;
344  }
345 
346  LOGGING_DEBUG_C(DriverSVH, resetChannel, "Channel " << m_reset_order[i] << " reset success = " << reset_success << endl);
347 
348  // set all reset flag
349  reset_all_success = reset_all_success && reset_success;
350  }
351 
352 
353 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
354  // In case we still told the user that this was an issue, it is clearly resolved now.
355  if (reset_all_success && m_ws_broadcaster)
356  {
357  m_ws_broadcaster->robot->clearHint(eHT_RESET_FAILED);
358  m_ws_broadcaster->robot->clearHint(eHT_NOT_RESETTED);
359  m_ws_broadcaster->sendHints(); // Hints are Transmitted Manually
360  }
361 #endif
362 
363  return reset_all_success;
364  }
365  else if (channel > eSVH_ALL && eSVH_ALL < eSVH_DIMENSION)
366  {
367  // Tell the websockets
368  MovementState last_movement_state = m_movement_state;
370 
371 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
372  if (m_ws_broadcaster)
373  {
374  m_ws_broadcaster->robot->setJointEnabled(false,channel);
375  m_ws_broadcaster->robot->setJointHomed(false,channel);
376  }
377 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
378 
379 
380  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Start homing channel " << channel << endl);
381 
382  if (!m_is_switched_off[channel])
383  {
384  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Setting reset position values for controller of channel " << channel << endl);
385 
387 
388  // reset homed flag
389  m_is_homed[channel] = false;
390 
391  // read default home settings for channel
392  SVHHomeSettings home = m_home_settings[channel];
393 
394  SVHPositionSettings pos_set;
395  SVHCurrentSettings cur_set;
396  m_controller->getPositionSettings(channel, pos_set);
397  m_controller->getCurrentSettings(channel, cur_set);
398 
399  // find home position
401  int32_t position = 0;
402 
403  if (home.direction > 0)
404  {
405  position = static_cast<int32_t>(pos_set.wmx);
406  }
407  else
408  {
409  position = static_cast<int32_t>(pos_set.wmn);
410  }
411 
412  LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Driving channel " << channel << " to hardstop. Detection thresholds: Current MIN: "<< home.resetCurrentFactor * cur_set.wmn << "mA MAX: "<< home.resetCurrentFactor * cur_set.wmx <<"mA" << endl);
413 
414  m_controller->setControllerTarget(channel, position);
415  m_controller->enableChannel(channel);
416 
417  SVHControllerFeedback control_feedback_previous;
418  SVHControllerFeedback control_feedback;
419 
420  // initialize timeout
423  // Debug helper to just notify about fresh stales
424  bool stale_notification_sent = false;
425 
426  for (size_t hit_count = 0; hit_count < 10; )
427  {
428  m_controller->setControllerTarget(channel, position);
429  //m_controller->requestControllerFeedback(channel);
430  m_controller->getControllerFeedback(channel, control_feedback);
431 
432  // Quite extensive Current output!
433  if ((icl_core::TimeStamp::now() - start_time_log).milliSeconds() > 250)
434  {
435  LOGGING_INFO_C(DriverSVH, SVHFingerManager,"Resetting Channel "<< channel << ":" << m_controller->m_channel_description[channel] << " current: " << control_feedback.current << " mA" << endl);
436  start_time_log = icl_core::TimeStamp::now();
437  }
438 
439  if ((home.resetCurrentFactor * cur_set.wmn >= control_feedback.current) || (control_feedback.current >= home.resetCurrentFactor * cur_set.wmx))
440  {
441  hit_count++;
442  LOGGING_TRACE_C(DriverSVH, SVHFingerManager,"Resetting Channel "<< channel << ":" << m_controller->m_channel_description[channel] << " Hit Count increased: " << hit_count << endl);
443  }
444  else if (hit_count > 0)
445  {
446  hit_count--;
447  LOGGING_TRACE_C(DriverSVH, SVHFingerManager,"Resetting Channel "<< channel << ":" << m_controller->m_channel_description[channel] << " Hit Count Decreased: " << hit_count << endl);
448  }
449 
450  // check for time out: Abort, if position does not change after homing timeout.
451  if ((icl_core::TimeStamp::now() - start_time).tsSec() > m_homing_timeout)
452  {
454  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Timeout: Aborted finding home position for channel " << channel << endl);
455  // Timeout could mean serious hardware issues or just plain wrong settings
456 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
457 
458  if (m_ws_broadcaster)
459  {
460  m_ws_broadcaster->robot->setHint(eHT_RESET_FAILED);
461  m_ws_broadcaster->sendHints(); // Hints are Transmitted Manually
462  }
463 #endif
464  return false;
465  }
466 
467  // reset time of position changes
468  if (control_feedback.position != control_feedback_previous.position)
469  {
470  start_time = icl_core::TimeStamp::now();
471  if (stale_notification_sent)
472  {
473  LOGGING_TRACE_C(DriverSVH, SVHFingerManager,"Resetting Channel "<< channel << ":" << m_controller->m_channel_description[channel] << " Stale resolved, continuing detection" << endl);
474  stale_notification_sent = false;
475  }
476  }
477  else
478  {
479  if (!stale_notification_sent)
480  {
481  LOGGING_TRACE_C(DriverSVH, SVHFingerManager,"Resetting Channel "<< channel << ":" << m_controller->m_channel_description[channel] << " Stale detected. Starting Timeout" << endl);
482  stale_notification_sent = true;
483  }
484  }
485 
486  // save previous control feedback
487  control_feedback_previous = control_feedback;
488  }
489 
490  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Hit counter of " << channel << " reached." << endl);
491 
493 
494  // set reference values
495  m_position_min[channel] = static_cast<int32_t>(control_feedback.position + home.minimumOffset);
496  m_position_max[channel] = static_cast<int32_t>(control_feedback.position + home.maximumOffset);
497  m_position_home[channel] = static_cast<int32_t>(control_feedback.position + home.idlePosition);
498  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Setting soft stops for Channel " << channel << " min pos = " << m_position_min[channel]
499  << " max pos = " << m_position_max[channel] << " home pos = " << m_position_home[channel] << endl);
500 
501  position = static_cast<int32_t>(control_feedback.position + home.idlePosition);
502 
503  // go to idle position
504  m_controller->enableChannel(channel);
505  while (true)
506  {
507  m_controller->setControllerTarget(channel, position);
508  //m_controller->requestControllerFeedback(channel);
509  m_controller->getControllerFeedback(channel, control_feedback);
510 
511  if (abs(position - control_feedback.position) < 1000)
512  {
513  break;
514  }
515  }
517 
518  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Restoring default position values for controller of channel " << channel << endl);
520  }
521  else
522  {
523 
524  LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Channel " << channel << "switched of by user, homing is set to finished" << endl);
525  }
526 
527 
528  m_is_homed[channel] = true;
529 
530  // Check if this reset has trigger the reset of all the Fingers
531  bool reset_all_success = true;
532  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
533  {
534  reset_all_success == reset_all_success && m_is_homed[channel];
535  }
536 
537  if (reset_all_success)
538  {
539 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
540  // In case we still told the user that this was an issue, it is clearly resolved now.
541  if (m_ws_broadcaster)
542  {
543  m_ws_broadcaster->robot->clearHint(eHT_RESET_FAILED);
544  m_ws_broadcaster->robot->clearHint(eHT_NOT_RESETTED);
545  m_ws_broadcaster->sendHints(); // Hints are Transmitted Manually
546  }
547 #endif
549  }
550  else
551  {
552  setMovementState(last_movement_state);
553  }
554 
555 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
556  if (m_ws_broadcaster)
557  {
558  m_ws_broadcaster->robot->setJointHomed(true,channel);
559  }
560 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
561 
562  LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Successfully homed channel " << channel << endl);
563 
564  return true;
565  }
566  else
567  {
568  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Channel " << channel << " is out of bounds!" << endl);
569  return false;
570  }
571  }
572  else
573  {
574  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not reset channel " << channel << ": No connection to SCHUNK five finger hand!" << endl);
575  return false;
576  }
577 }
578 
579 // enables controller of channel
581 {
582  if (isConnected() && isHomed(channel))
583  {
584  if (channel == eSVH_ALL)
585  {
586  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
587  {
588  // Just for safety, enable chanels in the same order as we have resetted them (otherwise developers might geht confused)
589  SVHChannel real_channel = static_cast<SVHChannel>(m_reset_order[i]);
590  if (!m_is_switched_off[real_channel])
591  {
592  // recursion to get the other updates corresponing with activation of a channel
593  enableChannel(real_channel);
594  }
595  }
596  }
597  else if (channel > eSVH_ALL && eSVH_ALL < eSVH_DIMENSION)
598  {
599  // Note: This part is another one of thise places where the names can lead to confusion. I am sorry about that
600  // Switched off is a logical term. The user has chosen NOT to use this channel because of hardware trouble.
601  // To enable a smooth driver behaviour all replys regarding these channels will be answered in the most positive way
602  // the caller could expect. Enabled refers to the actual enabled state of the hardware controller loops that drive the motors.
603  // As the user has chosen not to use certain channels we explicitly do NOT enable these but tell a calling driver that we did
604  if (!m_is_switched_off[channel])
605  {
606  m_controller->enableChannel(channel);
607  }
608 
609 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
610  if (m_ws_broadcaster)
611  {
612  m_ws_broadcaster->robot->setJointEnabled(true,channel);
613  }
614 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
615 
617  if (isEnabled(eSVH_ALL))
618  {
620  }
621  }
622  return true;
623  }
624  return false;
625 }
626 
628 {
629  if (channel == eSVH_ALL)
630  {
631  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
632  {
633  disableChannel(static_cast<SVHChannel>(i));
634  }
635  }
636  else
637  {
638  if (!m_is_switched_off[channel])
639  {
640  m_controller->disableChannel(channel);
641  }
642 
643 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
644  if (m_ws_broadcaster)
645  {
646  m_ws_broadcaster->robot->setJointEnabled(false,channel);
647  }
648 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
649 
651 
652  bool all_disabled = true;
653  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
654  {
655  // Aggain only check channels that are not switched off. Switched off channels will always answer that they are enabled
656  all_disabled = all_disabled && (m_is_switched_off[channel] ||!isEnabled(static_cast<SVHChannel>(i)));
657  }
658  if (all_disabled)
659  {
661  }
662 
663  }
664 }
665 
667 {
668  if (isConnected())
669  {
671  return true;
672  }
673 
674  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Feedback for channel " << channel << " could not be requested. FM is not connected to HW." << endl);
675  return false;
676 }
677 
678 // returns actual position value for given channel
679 bool SVHFingerManager::getPosition(const SVHChannel &channel, double &position)
680 {
681  SVHControllerFeedback controller_feedback;
682  if ((channel >=0 && channel < eSVH_DIMENSION) && isHomed(channel) && m_controller->getControllerFeedback(channel, controller_feedback))
683  {
684  // Switched off channels will always remain at zero position as the tics we get back migh be total gibberish
685  if (m_is_switched_off[channel])
686  {
687  position = 0.0;
688  return true;
689  }
690 
691  //int32_t cleared_position_ticks = controller_feedback.position;
692  position = convertTicks2Rad(channel,controller_feedback.position);
693 
694  // Safety overwrite: If controller drives to a negative position (should not happen but might in case the soft stops are placed badly)
695  // we cannot get out because inputs smaller than 0 will be ignored
696  if (position < 0)
697  {
698  position = 0.0;
699  }
700 
701  // DISABLED as the output was realy spamming everything else :)
702  //LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Channel " << channel << ": position_ticks = " << controller_feedback.position
703  // << " | cleared_position_ticks = " << cleared_position_ticks << " | position rad = " << position << endl);
704  return true;
705  }
706  else
707  {
708  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Could not get postion for channel " << channel << endl);
709  return false;
710  }
711 }
712 
713 
714 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
715 void SVHFingerManager::receivedHintMessage(const int &hint)
716 {
717  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Received a special command to clear error :" << hint << endl);
718  switch (hint)
719  {
721  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Retrying connection with device handle: " << m_serial_device << endl);
723  break;
725  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Retrying connection with device handle: " << m_serial_device << endl);
727  break;
728  case eHT_NOT_RESETTED:
729  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Resetting ALL fingers " << endl);
731  break;
732  case eHT_NOT_CONNECTED:
733  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Retrying connection with device handle: " << m_serial_device << endl);
735  break;
736  case eHT_RESET_FAILED:
737  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Resetting ALL fingers " << endl);
739  break;
741  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "No specific action associated with command" << hint << endl);
742  break;
744  LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "No specific action associated with command" << hint << endl);
745  break;
746  default:
747  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Special error clearing command " << hint << " could not be mapped. No action is taken please contact support if this happens." << endl);
748  break;
749  }
750 }
751 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
752 
753 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
754 void SVHFingerManager::updateWebSocket()
755 {
756  if (m_ws_broadcaster)
757  {
758  double position;
759  //double current // will be implemented in future releases
760  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
761  {
762  // NOTE: Although the call to getPosition and current cann fail due to multiple reason, the only one we would encounter with these calls is a
763  // non-homed finger. So it is quite safe to assume that the finger is NOT homed if these calls fail and we can do without multiple acces to the homed variable
764 
765  if (isHomed(static_cast<SVHChannel>(i)) && getPosition(static_cast<SVHChannel>(i),position)) // && (getCurrent(i,current))
766  {
767  m_ws_broadcaster->robot->setJointPosition(position,i);
768  //m_ws_broadcaster>robot>setJointCurrent(current,i); // will be implemented in future releases
769  }
770  else
771  {
772  m_ws_broadcaster->robot->setJointHomed(false,i);
773  }
774 
775  // One of the few places we actually need to call the sendstate as this function is periodically called by the feedback polling thread
776  if (!m_ws_broadcaster->sendState())
777  {
778  //LOGGING_INFO_C(DriverSVH, SVHFingerManager, "Can't send ws_broadcaster state - reconnect pending..." << endl);
779  }
780  }
781  }
782 }
783 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
784 
785 
786 
787 
788 
789 // returns actual current value for given channel
790 bool SVHFingerManager::getCurrent(const SVHChannel &channel, double &current)
791 {
792  SVHControllerFeedback controller_feedback;
793  if ((channel >=0 && channel < eSVH_DIMENSION) && isHomed(channel) && m_controller->getControllerFeedback(channel, controller_feedback))
794  {
795  current = controller_feedback.current;
796  return true;
797  }
798  else
799  {
800  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Could not get current for channel " << channel << endl);
801  return false;
802  }
803 }
804 
805 // set all target positions at once
806 bool SVHFingerManager::setAllTargetPositions(const std::vector<double>& positions)
807 {
808  if (isConnected())
809  {
810  // check size of position vector
811  if (positions.size() == eSVH_DIMENSION)
812  {
813  // create target positions vector
814  std::vector<int32_t> target_positions(eSVH_DIMENSION, 0);
815 
816  bool reject_command = false;
817  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
818  {
819  SVHChannel channel = static_cast<SVHChannel>(i);
820 
821  // enable all homed and disabled channels.. except its switched of
822  if (!m_is_switched_off[channel] && isHomed(channel) && !isEnabled(channel))
823  {
824  enableChannel(channel);
825  }
826 
827  // convert all channels to ticks
828  target_positions[channel] = convertRad2Ticks(channel, positions[channel]);
829 
830  // check for out of bounds (except the switched off channels)
831  if (!m_is_switched_off[channel] && !isInsideBounds(channel, target_positions[channel]))
832  {
833  reject_command = true;
834 
835  }
836  }
837 
838  // send target position vector to controller and SCHUNK hand
839  if (!reject_command)
840  {
841  m_controller->setControllerTargetAllChannels(target_positions);
842  return true;
843  }
844  else
845  {
846  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Could not set target position vector: At least one channel is out of bounds!" << endl);
847  return false;
848  }
849 
850  }
851  else
852  {
853  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Size of target position vector wrong: size = " << positions.size() << " expected size = " << (int)eSVH_DIMENSION << endl);
854  return false;
855  }
856  }
857  else
858  {
860  {
861  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set target position vector: No connection to SCHUNK five finger hand!" << endl);
863  }
864  return false;
865  }
866 }
867 
868 bool SVHFingerManager::setTargetPosition(const SVHChannel &channel, double position, double current)
869 {
870  if (isConnected())
871  {
872  if (channel >= 0 && channel < eSVH_DIMENSION)
873  {
874  if (m_is_switched_off[channel])
875  {
876  // Switched off channels behave transparent so we return a true value while we ignore the input
877  LOGGING_TRACE_C(DriverSVH, SVHFingerManager, "Target position for channel " << channel << " was ignored as it is switched off by the user"<< endl);
878  return true;
879  }
880 
881 
882  if (isHomed(channel))
883  {
884  int32_t target_position = convertRad2Ticks(channel, position);
885 
886  //Disabled as the output will spam everything
887  //LOGGING_DEBUG_C(DriverSVH, SVHFingerManager, "Target position for channel " << channel << " = " << target_position << endl);
888 
889  // check for bounds
890  if (isInsideBounds(channel, target_position))
891  {
892  if (!isEnabled(channel))
893  {
894  enableChannel(channel);
895  }
896 
897  m_controller->setControllerTarget(channel, target_position);
898  return true;
899  }
900  else
901  {
902  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Target position for channel " << channel << " out of bounds!" << endl);
903  return false;
904  }
905  }
906  else
907  {
908  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set target position for channel " << channel << ": Reset first!" << endl);
909  return false;
910  }
911  }
912  else
913  {
914  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set target position for channel " << channel << ": Illegal Channel" << endl);
915  return false;
916  }
917  }
918  else
919  {
920  // Give the Warning about no Connection exactly once! Otherwise this will immediately spam the log
922  {
923  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set target position for channel " << channel << ": No connection to SCHUNK five finger hand!" << endl);
925  }
926  return false;
927  }
928 }
929 
930 // return enable flag
932 {
933  if (channel==eSVH_ALL)
934  {
935  bool all_enabled = true;
936  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
937  {
938  all_enabled = all_enabled && isEnabled(static_cast<SVHChannel>(i));
939  // disabled for now, to noisy
940 // if (!isEnabled(static_cast<SVHChannel>(i)))
941 // {
942 // LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "All finger enabled check failed: Channel: " << channel << " : " << SVHController::m_channel_description[i] << " is not enabled" << endl);
943 // }
944  }
945 
946  return all_enabled;
947  }
948  else if (channel >=0 && channel < eSVH_DIMENSION)
949  {
950  // Switched off Channels will aways be reported as enabled to simulate everything is fine. Others need to ask the controller
951  // if the channel is realy switched on
952  // Note: i can see that based on the names this might lead to a little confusion... sorry about that but there are only limited number of
953  // words for not active ;) enabled refers to the actual state of the position and current controllers. So enabled
954  // means enabled on a hardware level. Switched off is a logical decission in this case. The user has specified this
955  // particular channel not to be used (due to hardware issues) and therefore the driver (aka the finger manager) will act
956  // AS IF the channel was enabled but is in fact switched off by the user. If you have a better variable name or a better
957  // idea how to handle that you are welcome to change it. (GH 2014-05-26)
958  return (m_is_switched_off[channel] || m_controller->isEnabled(channel));
959  }
960  else
961  {
962  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "isEnabled was requested for UNKNOWN Channel: " << channel << endl);
963  return false;
964  }
965 }
966 
968 {
969  if (channel == eSVH_ALL)
970  {
971  bool all_homed = true;
972  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
973  {
974  all_homed = all_homed && isHomed(static_cast<SVHChannel>(i));
975  if (!isHomed(static_cast<SVHChannel>(i)))
976  {
977  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "All finger homed check failed: Channel: " << i << " : " << SVHController::m_channel_description[i] << " is not homed" << endl);
978  }
979  }
980 
981  return all_homed;
982  }
983  else if (channel >=0 && channel < eSVH_DIMENSION)
984  {
985  // Channels that are switched off will always be reported as homed to simulate everything is fine. Others have to check
986  return (m_is_switched_off[channel] || m_is_homed[channel]);
987  }
988  else //should not happen but better be save than sorry
989  {
990  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "isHomed was requested for UNKNOWN Channel: " << channel << endl);
991  return false;
992  }
993 }
994 
996 {
997  m_movement_state = state;
998 
999 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
1000  if (m_ws_broadcaster)
1001  {
1002  m_ws_broadcaster->robot->setMovementState(state);
1003  }
1004 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
1005 }
1006 
1008 {
1009  if (channel >=0 && channel < eSVH_DIMENSION)
1010  {
1011  return m_controller->getCurrentSettings(channel, current_settings);
1012  }
1013  else
1014  {
1015  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not get current settings for unknown/unsupported channel " << channel << endl);
1016  return false;
1017  }
1018 }
1019 
1021 {
1022  if (channel >=0 && channel < eSVH_DIMENSION)
1023  {
1024  return m_controller->getPositionSettings(channel, position_settings);
1025  }
1026  else
1027  {
1028  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not get position settings for unknown/unsupported channel " << channel << endl);
1029  return false;
1030  }
1031 }
1032 
1033 bool SVHFingerManager::currentSettingsAreSafe(const SVHChannel &channel,const SVHCurrentSettings &current_settings)
1034 {
1035  bool settingsAreSafe = true;
1036 
1037  // Yeah i would also love to use static arrays here or other fancier things but c++98 is no fun dealing with these things
1038  // so i just wrote down the "dumb" approach, its just to veryfy absolute values anyhow
1039  switch (channel)
1040  {
1041  case eSVH_THUMB_FLEXION:
1042  settingsAreSafe = (current_settings.wmn >= -1800.0) &&
1043  (current_settings.wmx <= 1800.0);
1044  break;
1045  case eSVH_THUMB_OPPOSITION:
1046 
1047  settingsAreSafe = (current_settings.wmn >= -1800.0) &&
1048  (current_settings.wmx <= 1800.0);
1049  break;
1052  case eSVH_RING_FINGER:
1053  case eSVH_PINKY:
1054 
1055  settingsAreSafe = (current_settings.wmn >= -650.0) &&
1056  (current_settings.wmx <= 650.0);
1057  break;
1060 
1061  settingsAreSafe = (current_settings.wmn >= -1100.0) &&
1062  (current_settings.wmx <= 1100.0);
1063  break;
1064  case eSVH_FINGER_SPREAD:
1065  settingsAreSafe = (current_settings.wmn >= -1000.0) &&
1066  (current_settings.wmx <= 1000.0);
1067  break;
1068  default:
1069  // no valid channel was given anyway, this will be disregarded by the controller
1070  settingsAreSafe = true;
1071  break;
1072  }
1073 
1074  return settingsAreSafe;
1075 }
1076 
1077 // overwrite current parameters
1078 bool SVHFingerManager::setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
1079 {
1080 
1081  if (channel >=0 && channel < eSVH_DIMENSION)
1082  {
1083  // For now we will only evaluate this and print out warnings, however if you care to do these things.. go right ahead...
1084  if (!currentSettingsAreSafe(channel,current_settings))
1085  {
1086  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "WARNING!!! Current Controller Params for channel " << channel << " are dangerous! THIS MIGHT DAMAGE YOUR HARDWARE!!!" << endl);
1087 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
1088  if (m_ws_broadcaster)
1089  {
1090  m_ws_broadcaster->robot->setHint(eHT_DANGEROUS_CURRENTS);
1091  m_ws_broadcaster->sendHints(); // Hints are Transmitted Manually
1092  }
1093 #endif
1094  }
1095 
1096  // First of save the values
1097  m_current_settings[channel] = current_settings;
1098  m_current_settings_given[channel] = true;
1099 
1100  // In case the Hardware is connected, update the values
1101  if (isConnected())
1102  {
1103  m_controller->setCurrentSettings(channel, current_settings);
1104  }
1105  return true;
1106  }
1107  else
1108  {
1109  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set Current Controller Params for channel " << channel << ": No such channel" << endl);
1110  return false;
1111  }
1112 }
1113 
1114 // overwrite position parameters
1115 bool SVHFingerManager::setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
1116 {
1117 
1118  if (channel >=0 && channel < eSVH_DIMENSION)
1119  {
1120  // First of save the values
1121  m_position_settings[channel] = position_settings;
1122  m_position_settings_given[channel] = true;
1123 
1124  // In case the Hardware is connected, update the values
1125  if (isConnected())
1126  {
1127  m_controller->setPositionSettings(channel, position_settings);
1128  }
1129 
1130  return true;
1131  }
1132  else
1133  {
1134  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set Position Controller Params for channel " << channel << ": No such channel" << endl);
1135  return false;
1136  }
1137 }
1138 
1139 //overwirte home settings
1141 {
1142  if (channel >=0 && channel < eSVH_DIMENSION)
1143  {
1144  // First of save the values
1145  m_home_settings[channel] = home_settings;
1146  LOGGING_TRACE_C(DriverSVH,SVHFingerManager, "Channel " << channel << " setting new homing settings : ");
1147  LOGGING_TRACE_C(DriverSVH,SVHFingerManager, "Direction " << home_settings.direction << " " << "Min offset " << home_settings.minimumOffset << " "
1148  << "Max offset "<< home_settings.maximumOffset << " " << "idle pos " << home_settings.idlePosition << " "
1149  << "Range Rad " << home_settings.rangeRad << " " << "Reset Curr Factor " << home_settings.resetCurrentFactor << " " << endl
1150  );
1151 
1152  // Update the conversion factor for this finger:
1153  float range_ticks = m_home_settings[channel].maximumOffset - m_home_settings[channel].minimumOffset;
1154  m_ticks2rad[channel] = m_home_settings[channel].rangeRad / range_ticks * (-m_home_settings[channel].direction);
1155 
1156  return true;
1157  }
1158  else
1159  {
1160  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "Could not set homing settings for channel " << channel << ": No such channel" << endl);
1161  return false;
1162  }
1163 }
1164 
1166 {
1167  // homing parameters are important for software end stops
1168 
1169  // All values are based on the hardware description for maximum tics and maximum allowable range of movements
1170  // direction, minimum offset, maximum offset, idle position, range in rad, resetcurrent(factor)
1171  m_home_settings[eSVH_THUMB_FLEXION] = SVHHomeSettings(+1, -175.0e3f, -5.0e3f, -15.0e3f, 0.97, 0.75); // thumb flexion
1172  // Conservative value
1173  //m_home_settings[eSVH_THUMB_OPPOSITION] = SVHHomeSettings(+1, -105.0e3f, -5.0e3f, -15.0e3f, 0.99, 0.75); // thumb opposition
1174  // Value using the complete movemment range
1175  m_home_settings[eSVH_THUMB_OPPOSITION] = SVHHomeSettings(+1, -150.0e3f, -5.0e3f, -15.0e3f, 0.99, 0.75); // thumb opposition
1176  m_home_settings[eSVH_INDEX_FINGER_DISTAL] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 1.33, 0.75); // index finger distal joint
1177  m_home_settings[eSVH_INDEX_FINGER_PROXIMAL] = SVHHomeSettings(-1, 2.0e3f, 42.0e3f, 8.0e3f, 0.8, 0.75); // index finger proximal joint
1178  m_home_settings[eSVH_MIDDLE_FINGER_DISTAL] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 1.33, 0.75); // middle finger distal joint
1179  m_home_settings[eSVH_MIDDLE_FINGER_PROXIMAL] = SVHHomeSettings(-1, 2.0e3f, 42.0e3f, 8.0e3f, 0.8, 0.75); // middle finger proximal joint
1180  m_home_settings[eSVH_RING_FINGER] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 0.98, 0.75); // ring finger
1181  m_home_settings[eSVH_PINKY] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 0.98, 0.75); // pinky
1182  m_home_settings[eSVH_FINGER_SPREAD] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -25.0e3f,0.58, 0.4); // finger spread
1183 
1184  m_ticks2rad.resize(eSVH_DIMENSION, 0.0);
1185  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
1186  {
1187  float range_ticks = m_home_settings[i].maximumOffset - m_home_settings[i].minimumOffset;
1188  m_ticks2rad[i] = m_home_settings[i].rangeRad / range_ticks * (-m_home_settings[i].direction);
1189  }
1190 
1191 }
1192 
1193 
1194 
1195 std::vector<SVHCurrentSettings> SVHFingerManager::getDefaultCurrentSettings()
1196 {
1197  // BEWARE! Only change these values if you know what you are doing !! Setting wrong values could damage the hardware!!!
1198 
1199  std::vector<SVHCurrentSettings> current_settings(eSVH_DIMENSION);
1200 
1201 
1202  //SVHCurrentSettings cur_set_thumb = {-400.0f, 400.0f, 0.405f, 4e-6f, -400.0f, 400.0f, 0.850f, 85.0f, -500.0f, 500.0f}; // Backup values that are based on MeCoVis suggestions
1203  //SVHCurrentSettings cur_set_thumb_opposition = {-400.0f, 400.0f, 0.405f, 4e-6f, -400.0f, 400.0f, 0.90f, 85.0f, -800.0f, 800.0f}; // Backup values that are based on MeCoVis suggestions
1204  //SVHCurrentSettings cur_set_distal_joint = {-176.0f, 176.0f, 0.405f, 4e-6f, -300.0f, 300.0f, 0.850f, 85.0f, -254.0f, 254.0f}; // Backup values that are based on MeCoVis suggestions
1205  //SVHCurrentSettings cur_set_proximal_joint = {-167.0f, 167.0f, 0.405f, 4e-6f, -300.0f, 300.0f, 0.850f, 85.0f, -254.0f, 254.0f}; // Backup values that are based on MeCoVis suggestions
1206  //SVHCurrentSettings cur_set_finger_spread = {-200.0f, 200.0f, 0.405f, 4e-6f, -300.0f, 300.0f, 0.850f, 85.0f, -254.0f, 254.0f}; // Backup values that are based on MeCoVis suggestions
1207 
1208  // curr min, Curr max,ky(error output scaling),dt(time base),imn (integral windup min), imx (integral windup max), kp,ki,umn,umx (output limter)
1209  //SVHCurrentSettings cur_set_thumb(-500.0f, 500.0f, 0.405f, 4e-6f, -500.0f, 500.0f, 0.6f, 10.0f, -255.0f, 255.0f); // Much Smoother values that produce nice motions and are actually reasonabl
1210  //SVHCurrentSettings cur_set_thumb_opposition(-500.0f, 500.0f, 0.405f, 4e-6f, -500.0f, 500.0f, 0.6f, 10.0f, -255.0f, 255.0f); // Much Smoother values that produce nice motions and are actually reasonable
1211  //SVHCurrentSettings cur_set_distal_joint(-300.0f, 300.0f, 0.405f, 4e-6f, -300.0f, 300.0f, 0.3f, 10.0f, -255.0f, 255.0f); // Much Smoother values that produce nice motions and are actually reasonable
1212  //SVHCurrentSettings cur_set_proximal_joint(-350.0f, 350.0f, 0.405f, 4e-6f, -350.0f, 350.0f, 0.5f, 10.0f, -255.0f, 255.0f); // Much Smoother values that produce nice motions and are actually reasonable
1213  //SVHCurrentSettings cur_set_finger_spread(-300.0f, 300.0f, 0.405f, 4e-6f, -300.0f, 300.0f, 0.70f, 60.0f, -255.0f, 255.0f); // Somewhat better values based on the MeCoVis software
1214 
1215  // More accurate values used in the new param files for SVH V1
1216  SVHCurrentSettings cur_set_thumb( -500.0f, 500.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 0.6f, 10.0f, -255.0f, 255.0f);
1217  SVHCurrentSettings cur_set_thumb_opposition(-500.0f, 500.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1218  SVHCurrentSettings cur_set_distal_joint( -300.0f, 300.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1219  SVHCurrentSettings cur_set_proximal_joint( -350.0f, 350.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1220  SVHCurrentSettings cur_set_outer_joint( -300.0f, 300.0f, 0.405f, 4e-6f, -10.0f, 10.0f, 1.0f, 25.0f, -255.0f, 255.0f);
1221  SVHCurrentSettings cur_set_finger_spread( -500.0f, 500.0f, 0.405f, 4e-6f, -4.0f, 4.0f, 0.7f, 60.0f, -255.0f, 255.0f);
1222 
1223 
1224  current_settings[eSVH_THUMB_FLEXION] = m_current_settings_given[eSVH_THUMB_FLEXION] ? m_current_settings[eSVH_THUMB_FLEXION] :cur_set_thumb; // thumb flexion
1225  current_settings[eSVH_THUMB_OPPOSITION] = m_current_settings_given[eSVH_THUMB_OPPOSITION] ? m_current_settings[eSVH_THUMB_OPPOSITION] :cur_set_thumb_opposition; // thumb opposition
1226  current_settings[eSVH_INDEX_FINGER_DISTAL] = m_current_settings_given[eSVH_INDEX_FINGER_DISTAL] ? m_current_settings[eSVH_INDEX_FINGER_DISTAL] :cur_set_distal_joint; // index finger distal joint
1227  current_settings[eSVH_INDEX_FINGER_PROXIMAL] = m_current_settings_given[eSVH_INDEX_FINGER_PROXIMAL] ? m_current_settings[eSVH_INDEX_FINGER_PROXIMAL] :cur_set_proximal_joint; // index finger proximal joint
1228  current_settings[eSVH_MIDDLE_FINGER_DISTAL] = m_current_settings_given[eSVH_MIDDLE_FINGER_DISTAL] ? m_current_settings[eSVH_MIDDLE_FINGER_DISTAL] :cur_set_distal_joint; // middle finger distal joint
1229  current_settings[eSVH_MIDDLE_FINGER_PROXIMAL] = m_current_settings_given[eSVH_MIDDLE_FINGER_PROXIMAL] ? m_current_settings[eSVH_MIDDLE_FINGER_PROXIMAL] :cur_set_proximal_joint; // middle finger proximal joint
1230  current_settings[eSVH_RING_FINGER] = m_current_settings_given[eSVH_RING_FINGER] ? m_current_settings[eSVH_RING_FINGER] :cur_set_outer_joint; // ring finger
1231  current_settings[eSVH_PINKY] = m_current_settings_given[eSVH_PINKY] ? m_current_settings[eSVH_PINKY] :cur_set_outer_joint; // pinky
1232  current_settings[eSVH_FINGER_SPREAD] = m_current_settings_given[eSVH_FINGER_SPREAD] ? m_current_settings[eSVH_FINGER_SPREAD] :cur_set_finger_spread; // finger spread
1233 
1234  return current_settings;
1235 }
1236 
1240 std::vector<SVHPositionSettings> SVHFingerManager::getDefaultPositionSettings(const bool& reset)
1241 {
1242  std::vector<SVHPositionSettings> position_settings(eSVH_DIMENSION);
1243 
1244  // Original conservative settings
1245 // SVHPositionSettings pos_set_thumb = {-1.0e6f, 1.0e6f, 3.4e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f};
1246 // SVHPositionSettings pos_set_finger = {-1.0e6f, 1.0e6f, 8.5e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f};
1247 // SVHPositionSettings pos_set_spread = {-1.0e6f, 1.0e6f, 17.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f};
1248 
1249  // All Fingers 0.5rad/sec except the fingers (1.5)
1250 // SVHPositionSettings pos_set_thumb_flexion = {-1.0e6f, 1.0e6f, 26.288e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 400.0f};
1251 // SVHPositionSettings pos_set_thumb_opposition = {-1.0e6f, 1.0e6f, 15.151e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1252 // SVHPositionSettings pos_set_finger_index_distal = {-1.0e6f, 1.0e6f, 16.917e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 40.0f};
1253 // SVHPositionSettings pos_set_finger_index_proximal = {-1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f};
1254 // SVHPositionSettings pos_set_finger_middle_distal = {-1.0e6f, 1.0e6f, 16.917e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 10.0f};
1255 // SVHPositionSettings pos_set_finger_middle_proximal = {-1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f};
1256 // SVHPositionSettings pos_set_finger_ring = {-1.0e6f, 1.0e6f, 22.959e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1257 // SVHPositionSettings pos_set_finger_pinky = {-1.0e6f, 1.0e6f, 22.959e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1258 // SVHPositionSettings pos_set_spread = {-1.0e6f, 1.0e6f, 21.551e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1259 
1260  // All Fingers with a speed that will close the complete range of the finger in 0.5 Seconds (except the thumb that will take 4)
1261 // SVHPositionSettings pos_set_thumb_flexion = {-1.0e6f, 1.0e6f, 42.5e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 400.0f};
1262 // SVHPositionSettings pos_set_thumb_opposition = {-1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1263 // SVHPositionSettings pos_set_finger_index_distal = {-1.0e6f, 1.0e6f, 90.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 40.0f};
1264 // SVHPositionSettings pos_set_finger_index_proximal = {-1.0e6f, 1.0e6f, 80.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f};
1265 // SVHPositionSettings pos_set_finger_middle_distal = {-1.0e6f, 1.0e6f, 90.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 10.0f};
1266 // SVHPositionSettings pos_set_finger_middle_proximal = {-1.0e6f, 1.0e6f, 80.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f};
1267 // SVHPositionSettings pos_set_finger_ring = {-1.0e6f, 1.0e6f, 90.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1268 // SVHPositionSettings pos_set_finger_pinky = {-1.0e6f, 1.0e6f, 90.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1269 // SVHPositionSettings pos_set_spread = {-1.0e6f, 1.0e6f, 50.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f};
1270 
1271  // All Fingers with a speed that will close the complete range of the finger in 1 Seconds (except the thumb that will take 4)
1272  SVHPositionSettings pos_set_thumb_flexion (-1.0e6f, 1.0e6f, 65.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 400.0f);
1273  SVHPositionSettings pos_set_thumb_opposition (-1.0e6f, 1.0e6f, 50.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.1f, 100.0f);
1274  SVHPositionSettings pos_set_finger_index_distal (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 40.0f);
1275  SVHPositionSettings pos_set_finger_index_proximal (-1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f);
1276  SVHPositionSettings pos_set_finger_middle_distal (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 10.0f);
1277  SVHPositionSettings pos_set_finger_middle_proximal (-1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f);
1278  SVHPositionSettings pos_set_finger_ring (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1279  SVHPositionSettings pos_set_finger_pinky (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1280  SVHPositionSettings pos_set_spread (-1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1281 
1282 
1283  //Return either the default values or the ones given from outside
1284  position_settings[eSVH_THUMB_FLEXION] = m_position_settings_given[eSVH_THUMB_FLEXION] ? m_position_settings[eSVH_THUMB_FLEXION] : pos_set_thumb_flexion; // thumb flexion
1285  position_settings[eSVH_THUMB_OPPOSITION] = m_position_settings_given[eSVH_THUMB_OPPOSITION] ? m_position_settings[eSVH_THUMB_OPPOSITION] :pos_set_thumb_opposition; // thumb opposition
1286  position_settings[eSVH_INDEX_FINGER_DISTAL] = m_position_settings_given[eSVH_INDEX_FINGER_DISTAL] ? m_position_settings[eSVH_INDEX_FINGER_DISTAL] :pos_set_finger_index_distal; // index finger distal joint
1287  position_settings[eSVH_INDEX_FINGER_PROXIMAL] = m_position_settings_given[eSVH_INDEX_FINGER_PROXIMAL] ? m_position_settings[eSVH_INDEX_FINGER_PROXIMAL] :pos_set_finger_index_proximal; // index finger proximal joint
1288  position_settings[eSVH_MIDDLE_FINGER_DISTAL] = m_position_settings_given[eSVH_MIDDLE_FINGER_DISTAL] ? m_position_settings[eSVH_MIDDLE_FINGER_DISTAL] :pos_set_finger_middle_distal; // middle finger distal joint
1289  position_settings[eSVH_MIDDLE_FINGER_PROXIMAL] = m_position_settings_given[eSVH_MIDDLE_FINGER_PROXIMAL] ? m_position_settings[eSVH_MIDDLE_FINGER_PROXIMAL] :pos_set_finger_middle_proximal; // middle finger proximal joint
1290  position_settings[eSVH_RING_FINGER] = m_position_settings_given[eSVH_RING_FINGER] ? m_position_settings[eSVH_RING_FINGER] :pos_set_finger_ring; // ring finger
1291  position_settings[eSVH_PINKY] = m_position_settings_given[eSVH_PINKY] ? m_position_settings[eSVH_PINKY] :pos_set_finger_pinky; // pinky
1292  position_settings[eSVH_FINGER_SPREAD] = m_position_settings_given[eSVH_FINGER_SPREAD] ? m_position_settings[eSVH_FINGER_SPREAD] :pos_set_spread; // finger spread
1293 
1294  // Modify the reset speed in case these position settings are meant to be used during the reset
1295  if (reset)
1296  {
1297  for (size_t i = 0; i < eSVH_DIMENSION; ++i)
1298  {
1299  position_settings[i].dwmx = position_settings[i].dwmx * m_reset_speed_factor;
1300  }
1301  }
1302 
1303 
1304  return position_settings;
1305 }
1306 
1308 {
1309  if ((speed>= 0.0) && (speed <= 1.0))
1310  {
1311  m_reset_speed_factor = speed;
1312  }
1313  else
1314  {
1315  LOGGING_ERROR_C(DriverSVH, SVHFingerManager, "The reset speed value given: "<< speed << " is not valid. Please provide a value between 0.0 and 1.0, default is 0.2"<< endl);
1316  }
1317 }
1318 
1319 // Converts joint positions of a specific channel from RAD to ticks
1320 int32_t SVHFingerManager::convertRad2Ticks(const SVHChannel &channel,const double &position)
1321 {
1322  int32_t target_position = static_cast<int32_t>(position / m_ticks2rad[channel]);
1323 
1324  if (m_home_settings[channel].direction > 0)
1325  {
1326  target_position += m_position_max[channel];
1327  }
1328  else
1329  {
1330  target_position += m_position_min[channel];
1331  }
1332 
1333  return target_position;
1334 }
1335 
1336 // Converts Joint ticks of a specific channel back to RAD removing its offset in the process
1337 double SVHFingerManager::convertTicks2Rad(const SVHChannel &channel, const int32_t &ticks)
1338 {
1339  int32_t cleared_position_ticks;
1340 
1341  if (m_home_settings[channel].direction > 0)
1342  {
1343  cleared_position_ticks = ticks - m_position_max[channel];
1344  }
1345  else
1346  {
1347  cleared_position_ticks = ticks - m_position_min[channel];
1348  }
1349 
1350  return static_cast<double>(cleared_position_ticks * m_ticks2rad[channel]);
1351 }
1352 
1353 // Check bounds of target positions
1354 bool SVHFingerManager::isInsideBounds(const SVHChannel &channel, const int32_t &target_position)
1355 {
1356 
1357  // Switched off channels will always be reported as inside bounds
1358  if (m_is_switched_off[channel] || ((target_position >= m_position_min[channel]) && (target_position <= m_position_max[channel])))
1359  {
1360  return true;
1361  }
1362  else
1363  {
1364  LOGGING_WARNING_C(DriverSVH, SVHFingerManager, "Channel" << channel << " : " << SVHController::m_channel_description[channel] << " Target: " << target_position << "(" << convertTicks2Rad(channel,target_position) << "rad)" << " is out of bounds! [" << m_position_min[channel] << "/" << m_position_max[channel] << "]" << endl);
1365  return false;
1366  }
1367 }
1368 
1370 {
1372 }
1373 
1374 void SVHFingerManager::setResetTimeout(const int& resetTimeout)
1375 {
1376  m_reset_timeout = (resetTimeout>0)?resetTimeout:0;
1377 }
1378 
1380 {
1381  // As the firmware info takes longer we need to disable the polling during the request of the firmware informatio
1382  if (m_feedback_thread != NULL)
1383  {
1384  // wait until thread has stopped
1387  }
1388 
1389  // Tell the hardware to get the newest firmware information
1391  // Just wait a tiny amount
1392  icl_core::os::usleep(100);
1393 
1394  // Start the feedback process aggain
1395  if (m_feedback_thread != NULL)
1396  {
1397  // wait until thread has stopped
1399  }
1400 
1401  // Note that the Firmware will also be printed to the console by the controller. So in case you just want to know it no further action is required
1402  return m_controller->getFirmwareInfo();
1403 }
1404 
1405 }
SVHFirmwareInfo getFirmwareInfo()
get the latest stored Firmware information from the controller (NOT THE HARDWARE) ...
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.
float wmx
Reference signal maximum value.
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...
float wmn
Reference signal minimum value.
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 ...
void disableChannel(const SVHChannel &channel)
Disable one or all motor channels.
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
returns actual position controller settings of channel
static TimeSpan createFromMSec(int64_t msec)
#define LOGGING_INFO_C(streamname, classname, arg)
std::vector< SVHCurrentSettings > m_current_settings
Vector of current controller parameters for each finger (as given by external config) ...
bool setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
overwrite current parameters
void resetPackageCounts()
resetPackageCounts sets the sent and reveived package counts to zero
void setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
activate a new set of position controller settings for a specific channel
static TimeStamp now()
SVHFeedbackPollingThread * m_feedback_thread
pointer to svh controller
void disableChannel(const SVHChannel &channel)
disable controller of channel
f
TimeSpan abs(const TimeSpan &span)
int32_t convertRad2Ticks(const SVHChannel &channel, const double &position)
Converts joint positions of a specific channel from RAD to ticks factoring in the offset of the chann...
float minimumOffset
Minimum reachable tick limit, given as offset from the hard stop (soft limit)
unsigned int getSentPackageCount()
requests the number of sent packages. Request ist transferred to the serial interface that knows abou...
bool setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
overwrite position parameters
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
void setResetTimeout(const int &resetTimeout)
setResetTimeout Helper function to set the timout durind rest of fingers
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
Websocket handle for updating diagnostic backend (OPTIONAL)
int32_t position
Returned position value of the motor [Ticks].
int direction
Movement direction of the finger +1 or -1 home in positive or negative direction. ...
The SVHCurrentSettings save the current controller paramters for a single motor.
bool getCurrent(const SVHChannel &channel, double &current)
returns current value of channel
void setMovementState(const MovementState &state)
setMovementState Updates the movement state of the overll hand indicating the overall status ...
int8_t m_homing_timeout
vector storing reset flags for each finger
bool getControllerFeedback(const SVHChannel &channel, SVHControllerFeedback &controller_feedback)
request the latest stored controllerfeedback (current, position) from the controller.
bool connect(const std::string &dev_name)
Open serial device connection.
bool m_connection_feedback_given
Helper variable to check if feedback was printed (will be replaced by a better solution in the future...
float idlePosition
Idle position to move the fingers to after initialization.
unsigned int getReceivedPackageCount()
request the number of correctly received packages. This number is refreshed every time the serialinte...
void requestControllerState()
Request current controller state (mainly usefull for debug purposes)
bool isConnected()
returns connected state of finger manager
#define LOGGING_WARNING_C(streamname, classname, arg)
int usleep(unsigned long useconds)
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.
float dwmx
Reference signal delta maximum threshold.
float resetCurrentFactor
The resetCurrentFactor indicates how much of the maximum allowed current (of the controller) must be ...
bool resetChannel(const SVHChannel &channel)
reset function for channel
bool setAllTargetPositions(const std::vector< double > &positions)
set all target positions at once
void setControllerTarget(const SVHChannel &channel, const int32_t &position)
Set new position target for finger index.
std::vector< int32_t > m_position_min
min position vector for each channel
float wmx
Reference signal maximum value.
#define LOGGING_DEBUG_C(streamname, classname, arg)
std::vector< SVHHomeSettings > m_home_settings
Vector of home settings for each finger (as given by external config)
ThreadStream & endl(ThreadStream &stream)
bool isEnabled(const SVHChannel &channel)
Check if a channel was enabled.
bool isEnabled(const SVHChannel &channel)
returns true, if current channel has been enabled
double convertTicks2Rad(const SVHChannel &channel, const int32_t &ticks)
Converts joint positions of a specific channel from ticks to RAD factoring in the offset of the chann...
std::vector< SVHPositionSettings > m_position_settings
Vector of position controller parameters for each finger (as given by external config) ...
void requestControllerFeedback(const SVHChannel &channel)
request feedback (position and current) to a specific channel
std::vector< int32_t > m_position_home
home position after complete reset of each channel
void setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
activate a new set of current controller settings for a specific channel
The SVHFirmwareInfo holds the data of a firmware response from the hardware.
The SVHControllerFeedback saves the feedback of a single motor.
void disconnect()
disconnect serial device
const TimeSpan timeout(1, 0)
bool setTargetPosition(const SVHChannel &channel, double position, double current)
set target position of a channel
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
request the latest stored positionsettings from the controller
bool isHomed(const SVHChannel &channel)
returns true, if current channel has been resetted
static const char * m_channel_description[]
Description values to get the corresponding string value to a channel enum.
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...
int16_t current
Returned current value of the motor [mA].
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings)
request the latest stored currentsettings from the controller
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
float wmn
Reference signal minimum value.
This class controls the the SCHUNK five finger hand.
Definition: SVHController.h:77
void disconnect()
disconnect SCHUNK five finger hand
SVHFirmwareInfo getFirmwareInfo()
getFirmwareInfo Requests the firmware information from the harware, waits a bit and returns the last ...
void setControllerTargetAllChannels(const std::vector< int32_t > &positions)
Setting new position controller target for all fingers.
std::vector< SVHCurrentSettings > getDefaultCurrentSettings()
get default current settings. These are either values previously set from calling software or hardcod...
Thread for periodically requesting feedback messages from the SCHUNK five finger hand.
The SVHPositionSettings save the position controller paramters for a single motor.
bool enableChannel(const SVHChannel &channel)
enable controller of channel
bool requestControllerFeedback(const SVHChannel &channel)
send request controller feedback paket
void setResetSpeed(const float &speed)
setResetSpeed Set the speed percentage during reset
bool isInsideBounds(const SVHChannel &channel, const int32_t &target_position)
Check bounds of target positions.
void setDefaultHomeSettings()
initialize the homing settings with hardcoded defaults. These can be overwritten by the setHomeSettin...
float maximumOffset
Maximum reachable tick limt, given as an offset from the hard stop (soft limit)
bool connect(const std::string &dev_name="/dev/ttyUSB0", const unsigned int &_retry_count=3)
Open connection to SCHUNK five finger hand. Wait until expected return packages are received...
data sctructure for home positions
bool setHomeSettings(const SVHChannel &channel, const SVHHomeSettings &home_settings)
setHomeSettings set the home Settings which are maily used doring reset and provide the soft limit fo...
bool getPosition(const SVHChannel &channel, double &position)
returns position value of channel (will not acces hardware but return latest value) ...
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings)
returns actual current controller settings of channel
#define LOGGING_TRACE_C(streamname, classname, arg)
SVHFingerManager(const std::vector< bool > &disable_mask=std::vector< bool >(9, false), const uint32_t &reset_timeout=5)
std::vector< bool > m_current_settings_given
Information about the validity of externaly given values for the current settings (easier to use this...
std::vector< SVHPositionSettings > getDefaultPositionSettings(const bool &reset=false)
get default position settings. These are either values previously set from calling software or hardco...
SVHChannel
Channel indicates which motor to use in command calls. WARNING: DO NOT CHANGE THE ORDER OF THESE as i...
Definition: SVHController.h:56
#define LOGGING_ERROR_C(streamname, classname, arg)
bool currentSettingsAreSafe(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
currentSettingsAreSafe helper function to check for the most important values of the current settings...
SVHController * m_controller
pointer to svh controller
void requestFirmwareInfo()
request a transmission of formware information
void enableChannel(const SVHChannel &channel)
Enable one or all motor channels.


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