SVHFingerManager.cpp
Go to the documentation of this file.
1 //
3 // © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
4 // © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
5 //
6 // This file is part of the Schunk SVH Library.
7 //
8 // The Schunk SVH Library is free software: you can redistribute it and/or
9 // modify it under the terms of the GNU General Public License as published by
10 // the Free Software Foundation, either version 3 of the License, or (at your
11 // option) any later version.
12 //
13 // The Schunk SVH Library is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
16 // Public License for more details.
17 //
18 // You should have received a copy of the GNU General Public License along with
19 // the Schunk SVH Library. If not, see <https://www.gnu.org/licenses/>.
20 //
22 
23 //----------------------------------------------------------------------
39 //----------------------------------------------------------------------
42 
43 #include <chrono>
44 #include <cmath>
45 #include <functional>
46 #include <memory>
47 #include <thread>
48 
49 
50 namespace driver_svh {
51 
52 SVHFingerManager::SVHFingerManager(const std::vector<bool>& disable_mask,
53  const uint32_t& reset_timeout)
54  : m_controller(new SVHController())
55  , m_feedback_thread()
56  , m_connected(false)
57  , m_connection_feedback_given(false)
58  , m_homing_timeout(10)
59  , m_ticks2rad(0)
60  , m_position_min(SVH_DIMENSION, 0)
61  , m_position_max(SVH_DIMENSION, 0)
62  , m_position_home(SVH_DIMENSION, 0)
63  , m_is_homed(SVH_DIMENSION, false)
64  , m_is_switched_off(SVH_DIMENSION, false)
65  , m_diagnostic_encoder_state(SVH_DIMENSION, false)
66  , m_diagnostic_current_state(SVH_DIMENSION, false)
67  , m_diagnostic_current_maximum(SVH_DIMENSION, 0)
68  , m_diagnostic_current_minimum(SVH_DIMENSION, 0)
69  , m_diagnostic_position_maximum(SVH_DIMENSION, 0)
70  , m_diagnostic_position_minimum(SVH_DIMENSION, 0)
71  , m_diagnostic_deadlock(SVH_DIMENSION, 0)
72  , m_reset_speed_factor(0.2)
73  , m_reset_timeout(reset_timeout)
74  , m_current_settings(SVH_DIMENSION)
75  , m_current_settings_given(SVH_DIMENSION, false)
76  , m_position_settings(SVH_DIMENSION)
77  , m_position_settings_given(SVH_DIMENSION, false)
78  , m_home_settings(SVH_DIMENSION)
79  , m_serial_device("/dev/ttyUSB0")
80 {
81  // load home position default parameters
83 
84  // set default reset order of all channels
95 
96  for (size_t i = 0; i < SVH_DIMENSION; ++i)
97  {
98  m_is_switched_off[i] = disable_mask[i];
99  if (m_is_switched_off[i])
100  {
101  SVH_LOG_INFO_STREAM("SVHFingerManager",
102  "Joint: "
104  << " was disabled as per user request. It will not do anything!");
105  }
106  }
107 
115 
118 }
119 
121 {
122  if (m_connected)
123  {
124  disconnect();
125  }
126 
127  if (m_controller != NULL)
128  {
129  delete m_controller;
130  m_controller = NULL;
131  }
132 }
133 
134 bool SVHFingerManager::connect(const std::string& dev_name, const unsigned int& retry_count)
135 {
136  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
137  "Finger manager is trying to connect to the Hardware...");
138 
139  // Save device handle for next use
140  m_serial_device = dev_name;
141 
142 
143  if (m_connected)
144  {
145  disconnect();
146  }
147 
148  if (m_controller != NULL)
149  {
150  if (m_controller->connect(dev_name))
151  {
152  unsigned int num_retries = retry_count;
153  do
154  {
155  // Reset the package counts (in case a previous attempt was made)
157 
158  // load default position settings before the fingers are resetted
159  std::vector<SVHPositionSettings> position_settings = getDefaultPositionSettings(true);
160 
161  // load default current settings
162  std::vector<SVHCurrentSettings> current_settings = getDefaultCurrentSettings();
163 
165 
166  // initialize all channels
167  for (size_t i = 0; i < SVH_DIMENSION; ++i)
168  {
169  // request controller feedback to have a valid starting point
171 
172  // Actually set the new position settings
173  m_controller->setPositionSettings(static_cast<SVHChannel>(i), position_settings[i]);
174 
175  // set current settings
176  m_controller->setCurrentSettings(static_cast<SVHChannel>(i), current_settings[i]);
177  }
178 
179  // check for correct response from hardware controller
180  auto start_time = std::chrono::high_resolution_clock::now();
181  bool timeout = false;
182  unsigned int received_count = 0;
183  unsigned int send_count = 0;
184  while (!timeout && !m_connected)
185  {
186  send_count = m_controller->getSentPackageCount();
187  received_count = m_controller->getReceivedPackageCount();
188  if (send_count == received_count)
189  {
190  m_connected = true;
191  SVH_LOG_INFO_STREAM("SVHFingerManager",
192  "Successfully established connection to SCHUNK five finger hand."
193  << "Send packages = " << send_count
194  << ", received packages = " << received_count);
195  }
196  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
197  "Try to connect to SCHUNK five finger hand: Send packages = "
198  << send_count << ", received packages = " << received_count);
199 
200  // check for timeout
201  if ((std::chrono::high_resolution_clock::now() - start_time) > m_reset_timeout)
202  {
203  timeout = true;
204  SVH_LOG_ERROR_STREAM("SVHFingerManager",
205  "Connection timeout! Could not connect to SCHUNK five finger hand."
206  << "Send packages = " << send_count
207  << ", received packages = " << received_count);
208  }
209  std::this_thread::sleep_for(std::chrono::microseconds(50000));
210  }
211 
212  // Try again, but ONLY if we at least got one package back, otherwise its futil
213  if (!m_connected)
214  {
215  if (received_count > 0 && num_retries >= 0)
216  {
217  num_retries--;
218  SVH_LOG_ERROR_STREAM("SVHFingerManager",
219  "Connection Failed! Send packages = "
220  << send_count << ", received packages = " << received_count
221  << ". Retrying, count: " << num_retries);
222  }
223  else
224  {
225  num_retries = 0;
226  SVH_LOG_ERROR_STREAM("SVHFingerManager",
227  "Connection Failed! Send packages = "
228  << send_count << ", received packages = " << received_count
229  << ". Not Retrying anymore.");
230  }
231  }
232  // Keep trying to reconnect several times because the brainbox often makes problems
233  } while (!m_connected && num_retries > 0);
234 
235 
236  if (!m_connected && num_retries <= 0)
237  {
238  SVH_LOG_ERROR_STREAM("SVHFingerManager",
239  "A Stable connection could NOT be made, however some packages where "
240  "received. Please check the hardware!");
241  }
242 
243 
244  if (m_connected)
245  {
246  // Request firmware information once at the beginning, it will print out on the console
248 
249  // initialize feedback polling thread
250  if (m_feedback_thread.joinable()) // clean reset
251  {
252  m_poll_feedback = false;
253  m_feedback_thread.join();
254  }
255  m_poll_feedback = true;
257  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
258  "Finger manager is starting the fedback polling thread");
259  }
260  else
261  {
262  // connection open but not stable: close serial port for better reconnect later
264  }
265  }
266  else
267  {
268  SVH_LOG_ERROR_STREAM("SVHFingerManager", "Connection FAILED! Device could NOT be opened");
269  }
270  }
271 
272  return m_connected;
273 }
274 
276 {
277  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
278  "Finger manager is trying to discoconnect to the Hardware...");
279  m_connected = false;
281 
282  // Disable Polling
283  m_poll_feedback = false;
284  if (m_feedback_thread.joinable())
285  {
286  m_feedback_thread.join();
287  SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Feedback thread terminated");
288  }
289 
290  // Tell the Controller to terminate the rest
291  if (m_controller != NULL)
292  {
294  }
295 }
296 
299 {
300  if (m_connected)
301  {
302  // reset all channels
303  if (channel == SVH_ALL)
304  {
305  bool reset_all_success = true;
306  for (size_t i = 0; i < SVH_DIMENSION; ++i)
307  {
308  // try three times to reset each finger
309  size_t max_reset_counter = 3;
310  bool reset_success = false;
311  while (!reset_success && max_reset_counter > 0)
312  {
313  SVHChannel channel = static_cast<SVHChannel>(m_reset_order[i]);
314  reset_success = resetChannel(channel);
315  max_reset_counter--;
316  }
317 
319  "resetChannel", "Channel " << m_reset_order[i] << " reset success = " << reset_success);
320 
321  // set all reset flag
322  reset_all_success = reset_all_success && reset_success;
323  }
324 
325  return reset_all_success;
326  }
327  else if (channel > SVH_ALL && SVH_ALL < SVH_DIMENSION)
328  {
329  m_diagnostic_encoder_state[channel] = false;
330  m_diagnostic_current_state[channel] = false;
331 
332  SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Start homing channel " << channel);
333 
334  if (!m_is_switched_off[channel])
335  {
336  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
337  "Setting reset position values for controller of channel " << channel);
338 
340 
341  // reset homed flag
342  m_is_homed[channel] = false;
343 
344  // read default home settings for channel
345  SVHHomeSettings home = m_home_settings[channel];
346 
347  SVHPositionSettings pos_set;
348  SVHCurrentSettings cur_set;
349  m_controller->getPositionSettings(channel, pos_set);
350  m_controller->getCurrentSettings(channel, cur_set);
351 
352  // find home position
353  int32_t position = 0;
354 
355  if (home.direction > 0)
356  {
357  position = static_cast<int32_t>(pos_set.wmx);
358  }
359  else
360  {
361  position = static_cast<int32_t>(pos_set.wmn);
362  }
363 
364  SVH_LOG_INFO_STREAM("SVHFingerManager",
365  "Driving channel "
366  << channel << " to hardstop. Detection thresholds: Current MIN: "
367  << home.reset_current_factor * cur_set.wmn
368  << "mA MAX: " << home.reset_current_factor * cur_set.wmx << "mA");
369 
370  m_controller->setControllerTarget(channel, position);
371  m_controller->enableChannel(channel);
372 
373  SVHControllerFeedback control_feedback_previous;
374  SVHControllerFeedback control_feedback;
375 
376  // initialize timeout
377  auto start_time = std::chrono::high_resolution_clock::now();
378  auto start_time_log = std::chrono::high_resolution_clock::now();
379  // Debug helper to just notify about fresh stales
380  bool stale_notification_sent = false;
381 
382  for (size_t hit_count = 0; hit_count < 10;)
383  {
384  m_controller->setControllerTarget(channel, position);
385  // m_controller->requestControllerFeedback(channel);
386  m_controller->getControllerFeedback(channel, control_feedback);
387  // Timeout while no encoder ticks changed
388 
389  // Quite extensive Current output!
390  if (std::chrono::duration_cast<std::chrono::milliseconds>(
391  std::chrono::high_resolution_clock::now() - start_time_log) >
392  std::chrono::milliseconds(1000))
393  {
394  SVH_LOG_INFO_STREAM("SVHFingerManager",
395  "Resetting Channel "
396  << channel << ":" << m_controller->m_channel_description[channel]
397  << " current: " << control_feedback.current << " mA");
398  start_time_log = std::chrono::high_resolution_clock::now();
399  }
400 
401  double threshold = 80;
402  // have a look for deadlocks
403  if (home.direction == +1)
404  {
405  double delta =
406  control_feedback.current -
407  m_diagnostic_current_maximum[channel]; // without deadlocks delta should be positiv
408  if (delta <= -threshold)
409  {
410  if (std::abs(delta) > m_diagnostic_deadlock[channel])
411  {
412  m_diagnostic_deadlock[channel] = std::abs(delta);
413  }
414  }
415  }
416  else
417  {
418  double delta = control_feedback.current - m_diagnostic_current_minimum[channel];
419  if (delta >= threshold)
420  {
421  if (std::abs(delta) > m_diagnostic_deadlock[channel])
422  {
423  m_diagnostic_deadlock[channel] = std::abs(delta);
424  }
425  }
426  }
427 
428  // save the maximal/minimal current of the motor
429  if (control_feedback.current > m_diagnostic_current_maximum[channel])
430  {
431  m_diagnostic_current_maximum[channel] = control_feedback.current;
432  }
433  else
434  {
435  if (control_feedback.current < m_diagnostic_current_minimum[channel])
436  {
437  m_diagnostic_current_minimum[channel] = control_feedback.current;
438  }
439  }
440 
441  if ((home.reset_current_factor * cur_set.wmn >= control_feedback.current) ||
442  (control_feedback.current >= home.reset_current_factor * cur_set.wmx))
443  {
444  m_diagnostic_current_state[channel] =
445  true; // when in maximum the current controller is ok
446 
447  hit_count++;
448  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
449  "Resetting Channel "
450  << channel << ":" << m_controller->m_channel_description[channel]
451  << " Hit Count increased: " << hit_count);
452  }
453  else if (hit_count > 0)
454  {
455  hit_count--;
456  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
457  "Resetting Channel "
458  << channel << ":" << m_controller->m_channel_description[channel]
459  << " Hit Count Decreased: " << hit_count);
460  }
461 
462  // check for time out: Abort, if position does not change after homing timeout.
463  if ((std::chrono::high_resolution_clock::now() - start_time) > m_homing_timeout)
464  {
466  SVH_LOG_ERROR_STREAM("SVHFingerManager",
467  "Timeout: Aborted finding home position for channel " << channel);
468  // Timeout could mean serious hardware issues or just plain wrong settings
469  return false;
470  }
471 
472  // reset time if position changes
473  if (control_feedback.position != control_feedback_previous.position)
474  {
475  m_diagnostic_encoder_state[channel] = true;
476  // save the maximal/minimal position the channel can reach
477  if (control_feedback.position > m_diagnostic_position_maximum[channel])
478  m_diagnostic_position_maximum[channel] = control_feedback.position;
479  else if (control_feedback.position < m_diagnostic_position_minimum[channel])
480  m_diagnostic_position_minimum[channel] = control_feedback.position;
481 
482  start_time = std::chrono::high_resolution_clock::now();
483  if (stale_notification_sent)
484  {
485  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
486  "Resetting Channel "
487  << channel << ":"
489  << " Stale resolved, continuing detection");
490  stale_notification_sent = false;
491  }
492  }
493  else
494  {
495  if (!stale_notification_sent)
496  {
497  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
498  "Resetting Channel "
499  << channel << ":"
501  << " Stale detected. Starting Timeout");
502  stale_notification_sent = true;
503  }
504  }
505 
506  // save previous control feedback
507  control_feedback_previous = control_feedback;
508  // std::this_thread::sleep_for(std::chrono::microseconds(8000));
509  }
510  // give the last info with highes channel current value
511  SVH_LOG_INFO_STREAM("SVHFingerManager",
512  "Resetting Channel "
513  << channel << ":" << m_controller->m_channel_description[channel]
514  << " current: " << control_feedback.current << " mA");
515 
516  SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Hit counter of " << channel << " reached.");
517 
518 
519  // set reference values
520  m_position_min[channel] = static_cast<int32_t>(
521  control_feedback.position + std::min(home.minimum_offset, home.maximum_offset));
522  m_position_max[channel] = static_cast<int32_t>(
523  control_feedback.position + std::max(home.minimum_offset, home.maximum_offset));
524  m_position_home[channel] =
525  static_cast<int32_t>(control_feedback.position + home.direction * home.idle_position);
526  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
527  "Setting soft stops for Channel "
528  << channel << " min pos = " << m_position_min[channel]
529  << " max pos = " << m_position_max[channel]
530  << " home pos = " << m_position_home[channel]);
531 
532  // position will now be reached to release the motor and go into soft stops
533  position = m_position_home[channel];
534 
535  // go to idle position
536  // use the declared start_time variable for the homing timeout
537  start_time = std::chrono::high_resolution_clock::now();
538  while (true)
539  {
540  m_controller->setControllerTarget(channel, position);
541  // m_controller->requestControllerFeedback(channel);
542  m_controller->getControllerFeedback(channel, control_feedback);
543 
544  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
545  "Homing Channel "
546  << channel << ":" << m_controller->m_channel_description[channel]
547  << " current: " << control_feedback.current
548  << " mA, position ticks: " << control_feedback.position);
549 
550  if (abs(position - control_feedback.position) < 1000)
551  {
552  m_is_homed[channel] = true;
553  break;
554  }
555 
556  // if the finger hasn't reached the home position after m_homing_timeout there is an
557  // hardware error
558  if ((std::chrono::high_resolution_clock::now() - start_time) > m_homing_timeout)
559  {
560  m_is_homed[channel] = false;
561  SVH_LOG_ERROR_STREAM("SVHFingerManager",
562  "Channel " << channel << " home position is not reachable after "
563  << m_homing_timeout.count()
564  << "s! There could be an hardware error!");
565  break;
566  }
567  }
568 
570  // std::this_thread::sleep_for(std::chrono::microseconds(8000));
571  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
572  "Restoring default position values for controller of channel "
573  << channel);
575  }
576  else
577  {
578  SVH_LOG_INFO_STREAM("SVHFingerManager",
579  "Channel " << channel
580  << "switched of by user, homing is set to finished");
581  m_is_homed[channel] = true;
582  }
583 
584  // Check if this reset has trigger the reset of all the Fingers
585  // bool reset_all_success = true;
586  // for (size_t i = 0; i < SVH_DIMENSION; ++i)
587  // {
588  // reset_all_success == reset_all_success&& m_is_homed[channel];
589  // }
590 
591  SVH_LOG_INFO_STREAM("SVHFingerManager", "Successfully homed channel " << channel);
592 
593  return true;
594  }
595  else
596  {
597  SVH_LOG_ERROR_STREAM("SVHFingerManager", "Channel " << channel << " is out of bounds!");
598  return false;
599  }
600  }
601  else
602  {
603  SVH_LOG_ERROR_STREAM("SVHFingerManager",
604  "Could not reset channel "
605  << channel << ": No connection to SCHUNK five finger hand!");
606  return false;
607  }
608 }
609 
611  struct DiagnosticState& diagnostic_status)
612 {
613  if (channel >= 0 && channel < SVH_DIMENSION)
614  {
615  diagnostic_status.diagnostic_encoder_state = m_diagnostic_encoder_state[channel];
616  diagnostic_status.diagnostic_motor_state = m_diagnostic_current_state[channel];
617  diagnostic_status.diagnostic_current_maximum = m_diagnostic_current_maximum[channel];
618  diagnostic_status.diagnostic_current_minimum = m_diagnostic_current_minimum[channel];
619  diagnostic_status.diagnostic_position_maximum = m_diagnostic_position_maximum[channel];
620  diagnostic_status.diagnostic_position_minimum = m_diagnostic_position_minimum[channel];
621  diagnostic_status.diagnostic_deadlock = m_diagnostic_deadlock[channel];
622  return true;
623  }
624  else
625  {
626  SVH_LOG_ERROR_STREAM("SVHFingerManager",
627  "Could not get diagnostic status for unknown/unsupported channel "
628  << channel);
629  return false;
630  }
631 }
632 
633 
634 // enables controller of channel
636 {
637  if (isConnected() && isHomed(channel))
638  {
639  if (channel == SVH_ALL)
640  {
641  for (size_t i = 0; i < SVH_DIMENSION; ++i)
642  {
643  // Just for safety, enable channels in the same order as we have resetted them (otherwise
644  // developers might geht confused)
645  SVHChannel real_channel = static_cast<SVHChannel>(m_reset_order[i]);
646  if (!m_is_switched_off[real_channel])
647  {
648  // recursion to get the other updates corresponing with activation of a channel
649  enableChannel(real_channel);
650  }
651  }
652  }
653  else if (channel > SVH_ALL && SVH_ALL < SVH_DIMENSION)
654  {
655  // Note: This part is another one of these places where the names can lead to confusion. I am
656  // sorry about that Switched off is a logical term. The user has chosen NOT to use this
657  // channel because of hardware trouble. To enable a smooth driver behaviour all replys
658  // regarding these channels will be answered in the most positive way the caller could expect.
659  // Enabled refers to the actual enabled state of the hardware controller loops that drive the
660  // motors. As the user has chosen not to use certain channels we explicitly do NOT enable
661  // these but tell a calling driver that we did
662  if (!m_is_switched_off[channel])
663  {
664  m_controller->enableChannel(channel);
665  }
666  }
667  return true;
668  }
669  return false;
670 }
671 
673 {
674  if (channel == SVH_ALL)
675  {
676  for (size_t i = 0; i < SVH_DIMENSION; ++i)
677  {
678  disableChannel(static_cast<SVHChannel>(i));
679  }
680  }
681  else
682  {
683  if (!m_is_switched_off[channel])
684  {
685  m_controller->disableChannel(channel);
686  }
687 
688  bool all_disabled = true;
689  for (size_t i = 0; i < SVH_DIMENSION; ++i)
690  {
691  // Again only check channels that are not switched off. Switched off channels will always
692  // answer that they are enabled
693  all_disabled =
694  all_disabled && (m_is_switched_off[channel] || !isEnabled(static_cast<SVHChannel>(i)));
695  }
696  }
697 }
698 
700 {
701  if (isConnected())
702  {
704  return true;
705  }
706 
707  SVH_LOG_WARN_STREAM("SVHFingerManager",
708  "Feedback for channel "
709  << channel << " could not be requested. FM is not connected to HW.");
710  return false;
711 }
712 
713 // returns actual position value for given channel
714 bool SVHFingerManager::getPosition(const SVHChannel& channel, double& position)
715 {
716  SVHControllerFeedback controller_feedback;
717  if ((channel >= 0 && channel < SVH_DIMENSION) && isHomed(channel) &&
718  m_controller->getControllerFeedback(channel, controller_feedback))
719  {
720  // Switched off channels will always remain at zero position as the tics we get back migh be
721  // total gibberish
722  if (m_is_switched_off[channel])
723  {
724  position = 0.0;
725  return true;
726  }
727 
728  // int32_t cleared_position_ticks = controller_feedback.position;
729  position = convertTicks2Rad(channel, controller_feedback.position);
730 
731  // Safety overwrite: If controller drives to a negative position (should not happen but might in
732  // case the soft stops are placed badly) we cannot get out because inputs smaller than 0 will be
733  // ignored
734  if (position < 0)
735  {
736  position = 0.0;
737  }
738 
739  // DISABLED as the output was realy spamming everything else :)
740  // SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Channel " << channel << ": position_ticks = " <<
741  // controller_feedback.position
742  // << " | cleared_position_ticks = " << cleared_position_ticks << " | position
743  // rad = " << position);
744  return true;
745  }
746  else
747  {
748  SVH_LOG_WARN_STREAM("SVHFingerManager", "Could not get postion for channel " << channel);
749  return false;
750  }
751 }
752 
753 // returns actual current value for given channel
754 bool SVHFingerManager::getCurrent(const SVHChannel& channel, double& current)
755 {
756  SVHControllerFeedback controller_feedback;
757  if ((channel >= 0 && channel < SVH_DIMENSION) && isHomed(channel) &&
758  m_controller->getControllerFeedback(channel, controller_feedback))
759  {
760  current = controller_feedback.current;
761  return true;
762  }
763  else
764  {
765  SVH_LOG_WARN_STREAM("SVHFingerManager", "Could not get current for channel " << channel);
766  return false;
767  }
768 }
769 
770 // set all target positions at once
771 bool SVHFingerManager::setAllTargetPositions(const std::vector<double>& positions)
772 {
773  if (isConnected())
774  {
775  // check size of position vector
776  if (positions.size() == SVH_DIMENSION)
777  {
778  // create target positions vector
779  std::vector<int32_t> target_positions(SVH_DIMENSION, 0);
780 
781  bool reject_command = false;
782  for (size_t i = 0; i < SVH_DIMENSION; ++i)
783  {
784  SVHChannel channel = static_cast<SVHChannel>(i);
785 
786  // enable all homed and disabled channels.. except its switched of
787  if (!m_is_switched_off[channel] && isHomed(channel) && !isEnabled(channel))
788  {
789  enableChannel(channel);
790  }
791 
792  // convert all channels to ticks
793  target_positions[channel] = convertRad2Ticks(channel, positions[channel]);
794 
795  // check for out of bounds (except the switched off channels)
796  if (!m_is_switched_off[channel] && !isInsideBounds(channel, target_positions[channel]))
797  {
798  reject_command = true;
799  }
800  }
801 
802  // send target position vector to controller and SCHUNK hand
803  if (!reject_command)
804  {
805  m_controller->setControllerTargetAllChannels(target_positions);
806  return true;
807  }
808  else
809  {
811  "SVHFingerManager",
812  "Could not set target position vector: At least one channel is out of bounds!");
813  return false;
814  }
815  }
816  else
817  {
818  SVH_LOG_WARN_STREAM("SVHFingerManager",
819  "Size of target position vector wrong: size = "
820  << positions.size() << " expected size = " << (int)SVH_DIMENSION);
821  return false;
822  }
823  }
824  else
825  {
827  {
829  "SVHFingerManager",
830  "Could not set target position vector: No connection to SCHUNK five finger hand!");
832  }
833  return false;
834  }
835 }
836 
837 bool SVHFingerManager::setTargetPosition(const SVHChannel& channel, double position, double current)
838 {
839  if (isConnected())
840  {
841  if (channel >= 0 && channel < SVH_DIMENSION)
842  {
843  if (m_is_switched_off[channel])
844  {
845  // Switched off channels behave transparent so we return a true value while we ignore the
846  // input
847  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
848  "Target position for channel "
849  << channel << " was ignored as it is switched off by the user");
850  return true;
851  }
852 
853 
854  if (isHomed(channel))
855  {
856  int32_t target_position = convertRad2Ticks(channel, position);
857 
858  // Disabled as the output will spam everything
859  // SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Target position for channel " << channel << " =
860  // " << target_position);
861 
862  // check for bounds
863  if (isInsideBounds(channel, target_position))
864  {
865  if (!isEnabled(channel))
866  {
867  enableChannel(channel);
868  }
869 
870  m_controller->setControllerTarget(channel, target_position);
871  return true;
872  }
873  else
874  {
875  SVH_LOG_ERROR_STREAM("SVHFingerManager",
876  "Target position for channel " << channel << " out of bounds!");
877  return false;
878  }
879  }
880  else
881  {
882  SVH_LOG_ERROR_STREAM("SVHFingerManager",
883  "Could not set target position for channel " << channel
884  << ": Reset first!");
885  return false;
886  }
887  }
888  else
889  {
890  SVH_LOG_ERROR_STREAM("SVHFingerManager",
891  "Could not set target position for channel " << channel
892  << ": Illegal Channel");
893  return false;
894  }
895  }
896  else
897  {
898  // Give the Warning about no Connection exactly once! Otherwise this will immediately spam the
899  // log
901  {
902  SVH_LOG_ERROR_STREAM("SVHFingerManager",
903  "Could not set target position for channel "
904  << channel << ": No connection to SCHUNK five finger hand!");
906  }
907  return false;
908  }
909 }
910 
911 // return enable flag
913 {
914  if (channel == SVH_ALL)
915  {
916  bool all_enabled = true;
917  for (size_t i = 0; i < SVH_DIMENSION; ++i)
918  {
919  all_enabled = all_enabled && isEnabled(static_cast<SVHChannel>(i));
920  // disabled for now, to noisy
921  // if (!isEnabled(static_cast<SVHChannel>(i)))
922  // {
923  // SVH_LOG_WARN_STREAM("SVHFingerManager", "All finger enabled check failed: Channel: "
924  // << channel << " : " << SVHController::m_channel_description[i] << " is not
925  // enabled");
926  // }
927  }
928 
929  return all_enabled;
930  }
931  else if (channel >= 0 && channel < SVH_DIMENSION)
932  {
933  // Switched off Channels will aways be reported as enabled to simulate everything is fine.
934  // Others need to ask the controller if the channel is realy switched on Note: i can see that
935  // based on the names this might lead to a little confusion... sorry about that but there are
936  // only limited number of words for not active ;) enabled refers to the actual state of the
937  // position and current controllers. So enabled means enabled on a hardware level. Switched off
938  // is a logical decission in this case. The user has specified this particular channel not to be
939  // used (due to hardware issues) and therefore the driver (aka the finger manager) will act AS
940  // IF the channel was enabled but is in fact switched off by the user. If you have a better
941  // variable name or a better idea how to handle that you are welcome to change it. (GH
942  // 2014-05-26)
943  return (m_is_switched_off[channel] || m_controller->isEnabled(channel));
944  }
945  else
946  {
947  SVH_LOG_ERROR_STREAM("SVHFingerManager",
948  "isEnabled was requested for UNKNOWN Channel: " << channel);
949  return false;
950  }
951 }
952 
954 {
955  if (channel == SVH_ALL)
956  {
957  bool all_homed = true;
958  for (size_t i = 0; i < SVH_DIMENSION; ++i)
959  {
960  all_homed = all_homed && isHomed(static_cast<SVHChannel>(i));
961  if (!isHomed(static_cast<SVHChannel>(i)))
962  {
963  SVH_LOG_WARN_STREAM("SVHFingerManager",
964  "All finger homed check failed: Channel: "
965  << i << " : " << SVHController::m_channel_description[i]
966  << " is not homed");
967  }
968  }
969 
970  return all_homed;
971  }
972  else if (channel >= 0 && channel < SVH_DIMENSION)
973  {
974  // Channels that are switched off will always be reported as homed to simulate everything is
975  // fine. Others have to check
976  return (m_is_switched_off[channel] || m_is_homed[channel]);
977  }
978  else // should not happen but better be save than sorry
979  {
980  SVH_LOG_ERROR_STREAM("SVHFingerManager",
981  "isHomed was requested for UNKNOWN Channel: " << channel);
982  return false;
983  }
984 }
985 
987  SVHCurrentSettings& current_settings)
988 {
989  if (channel >= 0 && channel < SVH_DIMENSION)
990  {
991  return m_controller->getCurrentSettings(channel, current_settings);
992  }
993  else
994  {
995  SVH_LOG_ERROR_STREAM("SVHFingerManager",
996  "Could not get current settings for unknown/unsupported channel "
997  << channel);
998  return false;
999  }
1000 }
1001 
1003  SVHPositionSettings& position_settings)
1004 {
1005  if (channel >= 0 && channel < SVH_DIMENSION)
1006  {
1007  return m_controller->getPositionSettings(channel, position_settings);
1008  }
1009  else
1010  {
1011  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1012  "Could not get position settings for unknown/unsupported channel "
1013  << channel);
1014  return false;
1015  }
1016 }
1017 
1019 {
1020  if (channel >= 0 && channel < SVH_DIMENSION)
1021  {
1022  home_settings = m_home_settings[channel];
1023  return true;
1024  }
1025  else
1026  {
1027  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1028  "Could not get home settings for unknown/unsupported channel " << channel);
1029  return false;
1030  }
1031 }
1032 
1034  const SVHCurrentSettings& current_settings)
1035 {
1036  bool settings_are_safe = false;
1037 
1038  if (!isEnabled(SVH_ALL))
1039  {
1040  SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Fingers are not all enabled -> no safety tests");
1041  // befor the fingers are homed no finger-data are valid
1042  return true;
1043  }
1044 
1045  if (current_settings.wmx <=
1047  std::abs(m_diagnostic_position_minimum[channel])))
1048  {
1049  SVH_LOG_DEBUG_STREAM("SVHFingerManager", "Current settings are safe!");
1050  settings_are_safe = true;
1051  }
1052  else
1053  {
1054  SVH_LOG_WARN_STREAM("SVHFingerManager",
1055  "Current value given: " << current_settings.wmx << " is not valid.");
1057  "SVHFingerManager",
1058  " Please provide values between "
1059  << " 0 - "
1061  std::abs(m_diagnostic_position_minimum[channel]))
1062  << " [mA] or 0 - "
1063  << convertmAtoN(channel,
1065  std::max(m_diagnostic_current_maximum[channel],
1066  std::abs(m_diagnostic_position_minimum[channel])))
1067  << " [N]");
1068  }
1069 
1070  return settings_are_safe;
1071 }
1072 
1073 // overwrite current parameters
1075  const SVHCurrentSettings& current_settings)
1076 {
1077  if (channel >= 0 && channel < SVH_DIMENSION)
1078  {
1079  // For now we will prefent current settings with more current than possible
1080  if (!currentSettingsAreSafe(channel, current_settings))
1081  {
1082  // SVH_LOG_ERROR_STREAM("SVHFingerManager", "WARNING!!! Current Controller Params for channel
1083  // " << channel << " are dangerous! THIS MIGHT DAMAGE YOUR HARDWARE!!!");
1084  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1085  "WARNING!!! Current Controller Params for channel "
1086  << channel << " would be dangerous! Currents are limited!!!");
1087  return false;
1088  }
1089 
1090  // First of save the values
1091  m_current_settings[channel] = current_settings;
1092  m_current_settings_given[channel] = true;
1093 
1094  // In case the Hardware is connected, update the values
1095  if (isConnected())
1096  {
1097  m_controller->setCurrentSettings(channel, current_settings);
1098  }
1099  return true;
1100  }
1101  else
1102  {
1103  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1104  "Could not set Current Controller Params for channel "
1105  << channel << ": No such channel");
1106  return false;
1107  }
1108 }
1109 
1110 // overwrite position parameters
1112  const SVHPositionSettings& position_settings)
1113 {
1114  if (channel >= 0 && channel < SVH_DIMENSION)
1115  {
1116  // First of save the values
1117  m_position_settings[channel] = position_settings;
1118  m_position_settings_given[channel] = true;
1119 
1120  // In case the Hardware is connected, update the values
1121  if (isConnected())
1122  {
1123  m_controller->setPositionSettings(channel, position_settings);
1124  }
1125 
1126  return true;
1127  }
1128  else
1129  {
1130  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1131  "Could not set Position Controller Params for channel "
1132  << channel << ": No such channel");
1133  return false;
1134  }
1135 }
1136 
1137 // overwirte home settings
1139  const driver_svh::SVHHomeSettings& home_settings)
1140 {
1141  if (channel >= 0 && channel < SVH_DIMENSION)
1142  {
1143  // First of save the values
1144  m_home_settings[channel] = home_settings;
1145  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
1146  "Channel " << channel << " setting new homing settings : ");
1147  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
1148  "Direction " << home_settings.direction << " "
1149  << "Min offset " << home_settings.minimum_offset << " "
1150  << "Max offset " << home_settings.maximum_offset << " "
1151  << "idle pos " << home_settings.idle_position << " "
1152  << "Range Rad " << home_settings.range_rad << " "
1153  << "Reset Curr Factor " << home_settings.reset_current_factor
1154  << " ");
1155 
1156  // Update the conversion factor for this finger:
1157  float range_ticks =
1158  m_home_settings[channel].maximum_offset - m_home_settings[channel].minimum_offset;
1159  m_ticks2rad[channel] =
1160  m_home_settings[channel].range_rad / range_ticks * (-m_home_settings[channel].direction);
1161 
1162  return true;
1163  }
1164  else
1165  {
1166  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1167  "Could not set homing settings for channel " << channel
1168  << ": No such channel");
1169  return false;
1170  }
1171 }
1172 
1174 {
1175  // reset all channels
1176  if (channel == SVH_ALL)
1177  {
1178  for (size_t i = 0; i <= SVH_DIMENSION; ++i)
1179  {
1180  m_diagnostic_encoder_state[i] = false;
1181  m_diagnostic_current_state[i] = false;
1186  m_diagnostic_deadlock[i] = 0.0;
1187  }
1188  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
1189  "Diagnostic data for all channel reseted successfully");
1190  return true;
1191  }
1192  else
1193  {
1194  if (channel > 0 && channel <= SVH_DIMENSION)
1195  {
1196  m_diagnostic_encoder_state[channel] = false;
1197  m_diagnostic_current_state[channel] = false;
1198  m_diagnostic_current_maximum[channel] = 0.0;
1199  m_diagnostic_current_minimum[channel] = 0.0;
1200  m_diagnostic_position_maximum[channel] = 0.0;
1201  m_diagnostic_position_minimum[channel] = 0.0;
1202  SVH_LOG_DEBUG_STREAM("SVHFingerManager",
1203  "Diagnostic data for channel " << channel << " reseted successfully");
1204  return true;
1205  }
1206  else
1207  {
1208  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1209  "Could not reset diagnostic data for channel " << channel
1210  << ": No such channel");
1211  return false;
1212  }
1213  }
1214 }
1215 
1217 {
1218  // homing parameters are important for software end stops
1219 
1220  // All values are based on the hardware description for maximum tics and maximum allowable range
1221  // of movements direction, minimum offset, maximum offset, idle position, range in rad,
1222  // resetcurrent(factor)
1224  SVHHomeSettings(+1, -175.0e3f, -5.0e3f, -15.0e3f, 0.97, 0.75); // thumb flexion
1225  // Conservative value
1226  // m_home_settings[eSVH_THUMB_OPPOSITION] = SVHHomeSettings(+1, -105.0e3f, -5.0e3f,
1227  // -15.0e3f, 0.99, 0.75); // thumb opposition
1228  // Value using the complete movemment range
1230  SVHHomeSettings(+1, -150.0e3f, -5.0e3f, -15.0e3f, 0.99, 0.75); // thumb opposition
1232  SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 1.33, 0.75); // index finger distal joint
1234  SVHHomeSettings(-1, 2.0e3f, 42.0e3f, 8.0e3f, 0.8, 0.75); // index finger proximal joint
1236  SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 1.33, 0.75); // middle finger distal joint
1238  SVHHomeSettings(-1, 2.0e3f, 42.0e3f, 8.0e3f, 0.8, 0.75); // middle finger proximal joint
1240  SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 0.98, 0.75); // ring finger
1241  m_home_settings[SVH_PINKY] = SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -8.0e3f, 0.98, 0.75); // pinky
1243  SVHHomeSettings(+1, -47.0e3f, -2.0e3f, -25.0e3f, 0.58, 0.4); // finger spread
1244 
1245  m_ticks2rad.resize(SVH_DIMENSION, 0.0);
1246  for (size_t i = 0; i < SVH_DIMENSION; ++i)
1247  {
1248  float range_ticks = m_home_settings[i].maximum_offset - m_home_settings[i].minimum_offset;
1249  m_ticks2rad[i] = m_home_settings[i].range_rad / range_ticks * (-m_home_settings[i].direction);
1250  }
1251 }
1252 
1253 
1254 std::vector<SVHCurrentSettings> SVHFingerManager::getDefaultCurrentSettings()
1255 {
1256  // BEWARE! Only change these values if you know what you are doing !! Setting wrong values could
1257  // damage the hardware!!!
1258 
1259  std::vector<SVHCurrentSettings> current_settings(SVH_DIMENSION);
1260 
1261 
1262  // curr min, Curr max,ky(error output scaling),dt(time base),imn (integral windup min), imx
1263  // (integral windup max), kp,ki,umn,umx (output limter) More accurate values used in the new param
1264  // files for SVH V1
1265  SVHCurrentSettings cur_set_thumb(
1266  -500.0f, 500.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 0.6f, 10.0f, -255.0f, 255.0f);
1267  SVHCurrentSettings cur_set_thumb_opposition(
1268  -500.0f, 500.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1269  SVHCurrentSettings cur_set_distal_joint(
1270  -300.0f, 300.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1271  SVHCurrentSettings cur_set_proximal_joint(
1272  -350.0f, 350.0f, 0.405f, 4e-6f, -25.0f, 25.0f, 1.0f, 10.0f, -255.0f, 255.0f);
1273  SVHCurrentSettings cur_set_outer_joint(
1274  -300.0f, 300.0f, 0.405f, 4e-6f, -10.0f, 10.0f, 1.0f, 25.0f, -255.0f, 255.0f);
1275  SVHCurrentSettings cur_set_finger_spread(
1276  -500.0f, 500.0f, 0.405f, 4e-6f, -4.0f, 4.0f, 0.7f, 60.0f, -255.0f, 255.0f);
1277 
1278 
1281  : cur_set_thumb; // thumb flexion
1284  : cur_set_thumb_opposition; // thumb opposition
1287  : cur_set_distal_joint; // index finger distal joint
1288  current_settings[SVH_INDEX_FINGER_PROXIMAL] =
1291  : cur_set_proximal_joint; // index finger proximal joint
1292  current_settings[SVH_MIDDLE_FINGER_DISTAL] =
1295  : cur_set_distal_joint; // middle finger distal joint
1296  current_settings[SVH_MIDDLE_FINGER_PROXIMAL] =
1299  : cur_set_proximal_joint; // middle finger proximal joint
1302  : cur_set_outer_joint; // ring finger
1304  : cur_set_outer_joint; // pinky
1307  : cur_set_finger_spread; // finger spread
1308 
1309  return current_settings;
1310 }
1311 
1316 std::vector<SVHPositionSettings> SVHFingerManager::getDefaultPositionSettings(const bool& reset)
1317 {
1318  std::vector<SVHPositionSettings> position_settings(SVH_DIMENSION);
1319 
1320  // Original conservative settings
1321  // SVHPositionSettings pos_set_thumb = {-1.0e6f, 1.0e6f, 3.4e3f, 1.00f, 1e-3f, -500.0f, 500.0f,
1322  // 0.5f, 0.05f, 0.0f}; SVHPositionSettings pos_set_finger = {-1.0e6f, 1.0e6f, 8.5e3f, 1.00f,
1323  // 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f}; SVHPositionSettings pos_set_spread =
1324  // {-1.0e6f, 1.0e6f, 17.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f};
1325 
1326  // All Fingers with a speed that will close the complete range of the finger in 1 Seconds (except
1327  // the thumb that will take 4)
1328  SVHPositionSettings pos_set_thumb_flexion(
1329  -1.0e6f, 1.0e6f, 65.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 400.0f);
1330  SVHPositionSettings pos_set_thumb_opposition(
1331  -1.0e6f, 1.0e6f, 50.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.1f, 100.0f);
1332  SVHPositionSettings pos_set_finger_index_distal(
1333  -1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 40.0f);
1334  SVHPositionSettings pos_set_finger_index_proximal(
1335  -1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f);
1336  SVHPositionSettings pos_set_finger_middle_distal(
1337  -1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 10.0f);
1338  SVHPositionSettings pos_set_finger_middle_proximal(
1339  -1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.8f, 0.0f, 1000.0f);
1340  SVHPositionSettings pos_set_finger_ring(
1341  -1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1342  SVHPositionSettings pos_set_finger_pinky(
1343  -1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1344  SVHPositionSettings pos_set_spread(
1345  -1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.0f, 100.0f);
1346 
1347  // OLD (from diagnostics) - All Fingers with a speed that will close the complete range of the
1348  // finger in 1 Seconds (except the thumb that wikll take 4)
1349  // SVHPositionSettings pos_set_thumb_flexion (-1.0e6f, 1.0e6f, 65.0e3f, 1.00f, 1e-3f,
1350  // -500.0f, 500.0f, 0.5f, 0.05f, 0.0f); SVHPositionSettings pos_set_thumb_opposition
1351  // (-1.0e6f, 1.0e6f, 50.0e3f, 1.00f, 1e-3f, -4000.0f, 4000.0f, 0.05f, 0.1f, 0.0f);
1352  // SVHPositionSettings pos_set_finger_index_distal (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f,
1353  // -500.0f, 500.0f, 0.5f, 0.05f, 0.0f); SVHPositionSettings pos_set_finger_index_proximal
1354  // (-1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.3f, 0.05f, 0.0f);
1355  // SVHPositionSettings pos_set_finger_middle_distal (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f,
1356  // -500.0f, 500.0f, 0.5f, 0.05f, 0.0f); SVHPositisonSettings pos_set_finger_middle_proximal
1357  // (-1.0e6f, 1.0e6f, 40.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.3f, 0.05f, 0.0f);
1358  // SVHPositionSettings pos_set_finger_ring (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f,
1359  // -500.0f, 500.0f, 0.5f, 0.05f, 0.0f); SVHPositionSettings pos_set_finger_pinky
1360  // (-1.0e6f, 1.0e6f, 45.0e3f, 1.00f, 1e-3f, -500.0f, 500.0f, 0.5f, 0.05f, 0.0f);
1361  // SVHPositionSettings pos_set_spread (-1.0e6f, 1.0e6f, 25.0e3f, 1.00f, 1e-3f,
1362  // -500.0f, 500.0f, 0.5f, 0.05f, 0.0f);
1363 
1364 
1365  // Return either the default values or the ones given from outside
1368  : pos_set_thumb_flexion; // thumb flexion
1371  : pos_set_thumb_opposition; // thumb opposition
1372  position_settings[SVH_INDEX_FINGER_DISTAL] =
1375  : pos_set_finger_index_distal; // index finger distal joint
1376  position_settings[SVH_INDEX_FINGER_PROXIMAL] =
1379  : pos_set_finger_index_proximal; // index finger proximal joint
1380  position_settings[SVH_MIDDLE_FINGER_DISTAL] =
1383  : pos_set_finger_middle_distal; // middle finger distal joint
1384  position_settings[SVH_MIDDLE_FINGER_PROXIMAL] =
1387  : pos_set_finger_middle_proximal; // middle finger proximal joint
1390  : pos_set_finger_ring; // ring finger
1391  position_settings[SVH_PINKY] = m_position_settings_given[SVH_PINKY]
1393  : pos_set_finger_pinky; // pinky
1396  : pos_set_spread; // finger spread
1397 
1398  // Modify the reset speed in case these position settings are meant to be used during the reset
1399  if (reset)
1400  {
1401  for (size_t i = 0; i < SVH_DIMENSION; ++i)
1402  {
1403  position_settings[i].dwmx = position_settings[i].dwmx * m_reset_speed_factor;
1404  }
1405  }
1406 
1407 
1408  return position_settings;
1409 }
1410 
1412 {
1413  if ((speed >= 0.0) && (speed <= 1.0))
1414  {
1415  m_reset_speed_factor = speed;
1416  }
1417  else
1418  {
1420  "SVHFingerManager",
1421  "The reset speed value given: "
1422  << speed << " is not valid. Please provide a value between 0.0 and 1.0, default is 0.2");
1423  }
1424 }
1425 
1426 // Converts joint positions of a specific channel from RAD to ticks
1427 int32_t SVHFingerManager::convertRad2Ticks(const SVHChannel& channel, const double& position)
1428 {
1429  int32_t target_position = static_cast<int32_t>(position / m_ticks2rad[channel]);
1430 
1431  if (m_home_settings[channel].direction > 0)
1432  {
1433  target_position += m_position_max[channel];
1434  }
1435  else
1436  {
1437  target_position += m_position_min[channel];
1438  }
1439 
1440  return target_position;
1441 }
1442 
1443 // Converts Joint ticks of a specific channel back to RAD removing its offset in the process
1444 double SVHFingerManager::convertTicks2Rad(const SVHChannel& channel, const int32_t& ticks)
1445 {
1446  int32_t cleared_position_ticks;
1447 
1448  if (m_home_settings[channel].direction > 0)
1449  {
1450  cleared_position_ticks = ticks - m_position_max[channel];
1451  }
1452  else
1453  {
1454  cleared_position_ticks = ticks - m_position_min[channel];
1455  }
1456 
1457  return static_cast<double>(cleared_position_ticks * m_ticks2rad[channel]);
1458 }
1459 
1460 // Converts joint efforts of a specific channel from force [N] to current [mA]
1461 uint16_t SVHFingerManager::convertNtomA(const SVHChannel& channel, const double& effort)
1462 {
1463  uint16_t current;
1464  if (SVHController::CHANNEL_EFFORT_CONSTANTS[channel][0] != 0)
1465  {
1466  // y = a*x + b --> x = (y-b) / a
1467  // y = effort and x = current
1468  current = static_cast<uint16_t>(
1469  std::round((effort - SVHController::CHANNEL_EFFORT_CONSTANTS[channel][1]) /
1471  }
1472  else
1473  {
1474  current =
1475  static_cast<uint16_t>(m_max_current_percentage * m_diagnostic_current_maximum[channel]);
1476  }
1477 
1478  return current;
1479 }
1480 
1481 // Converts joint effort of a specific channel from current [mA] to force [N]
1482 double SVHFingerManager::convertmAtoN(const SVHChannel& channel, const int16_t& current)
1483 {
1484  float effort;
1485  // y = a*x + b
1486  // y = effort and x = current
1487  effort = SVHController::CHANNEL_EFFORT_CONSTANTS[channel][0] * std::abs(current) +
1489 
1490  return effort;
1491 }
1492 
1493 // Check bounds of target positions
1494 bool SVHFingerManager::isInsideBounds(const SVHChannel& channel, const int32_t& target_position)
1495 {
1496  // Switched off channels will always be reported as inside bounds
1497  if (m_is_switched_off[channel] || ((target_position >= m_position_min[channel]) &&
1498  (target_position <= m_position_max[channel])))
1499  {
1500  return true;
1501  }
1502  else
1503  {
1504  SVH_LOG_WARN_STREAM("SVHFingerManager",
1505  "Channel" << channel << " : "
1507  << " Target: " << target_position << "("
1508  << convertTicks2Rad(channel, target_position) << "rad)"
1509  << " is out of bounds! [" << m_position_min[channel] << "/"
1510  << m_position_max[channel] << "]");
1511  return false;
1512  }
1513 }
1514 
1516 {
1518 }
1519 
1520 void SVHFingerManager::setResetTimeout(const int& reset_timeout)
1521 {
1522  m_reset_timeout =
1523  (reset_timeout > 0) ? std::chrono::seconds(reset_timeout) : std::chrono::seconds(0);
1524 }
1525 
1526 bool SVHFingerManager::setMaxForce(float max_force)
1527 {
1528  if (max_force > 0 && max_force <= 1)
1529  {
1530  m_max_current_percentage = max_force;
1531  return true;
1532  }
1533  else
1534  {
1536  "SVHFingerManager",
1537  "Maximal Force / current should be in the range of [0,1], was set to: " << max_force);
1538  return false;
1539  }
1540 }
1541 
1542 float SVHFingerManager::setForceLimit(const SVHChannel& channel, float force_limit)
1543 {
1544  uint16_t current;
1545  current = convertNtomA(channel, force_limit);
1546 
1547  SVHCurrentSettings current_settings;
1548 
1549  current_settings = m_current_settings[channel];
1550 
1551  current_settings.wmx = current;
1552  current_settings.wmn = -static_cast<float>(current);
1553 
1554  if (setCurrentSettings(channel, current_settings))
1555  {
1556  return force_limit;
1557  }
1558  else
1559  {
1560  return 0.0;
1561  }
1562 }
1563 
1564 
1566  const unsigned int& retry_count)
1567 {
1568  // If firmware was read out befor do not ask for new firmware
1570  {
1571  bool was_connected = true;
1572 
1573  if (!m_connected)
1574  {
1575  was_connected = false;
1576  if (!m_controller->connect(dev_name))
1577  {
1578  SVH_LOG_ERROR_STREAM("SVHFingerManager", "Connection FAILED! Device could NOT be opened");
1581  return m_firmware_info;
1582  }
1583  }
1584 
1585  // As the firmware info takes longer we need to disable the polling during the request of the
1586  // firmware information
1587  m_poll_feedback = false;
1588  if (m_feedback_thread.joinable())
1589  {
1590  m_feedback_thread.join();
1591  }
1592 
1593  unsigned int num_retries = retry_count;
1594  do
1595  {
1596  // Tell the hardware to get the newest firmware information
1598  // Just wait a tiny amount
1599  std::this_thread::sleep_for(std::chrono::microseconds(100000));
1600  // Get the Version number if received yet, else 0.0
1602  --num_retries;
1603 
1605  {
1606  SVH_LOG_ERROR_STREAM("SVHFingerManager",
1607  "Getting Firmware Version failed,.Retrying, count: " << num_retries);
1608  }
1609  } while (num_retries > 0 && m_firmware_info.version_major == 0 &&
1611 
1612  // Start the feedback process aggain
1613  m_poll_feedback = true;
1614  m_feedback_thread = std::thread(&SVHFingerManager::pollFeedback, this);
1615 
1616  if (!was_connected)
1617  {
1619  }
1620  }
1621 
1622  // Note that the Firmware will also be printed to the console by the controller. So in case you
1623  // just want to know it no further action is required
1624  return m_firmware_info;
1625 }
1626 
1628 {
1629  while (m_poll_feedback)
1630  {
1631  if (isConnected())
1632  {
1634  }
1635  else
1636  {
1637  SVH_LOG_WARN_STREAM("SVHFeedbackPollingThread", "SCHUNK five finger hand is not connected!");
1638  }
1639  std::this_thread::sleep_for(std::chrono::milliseconds(100));
1640  }
1641 }
1642 
1643 } // namespace driver_svh
driver_svh::SVHFingerManager::setHomeSettings
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...
Definition: SVHFingerManager.cpp:1138
driver_svh::SVHFingerManager::convertNtomA
uint16_t convertNtomA(const SVHChannel &channel, const double &effort)
Converts joint efforts of a specific channel from force [N] to current [mA] factoring the effort_cons...
Definition: SVHFingerManager.cpp:1461
driver_svh::SVHController::getCurrentSettings
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings)
request the latest stored currentsettings from the controller
Definition: SVHController.cpp:737
driver_svh::SVHController::requestControllerState
void requestControllerState()
Request current controller state (mainly usefull for debug purposes)
Definition: SVHController.cpp:373
driver_svh::SVHFingerManager::disableChannel
void disableChannel(const SVHChannel &channel)
disable controller of channel
Definition: SVHFingerManager.cpp:672
driver_svh::SVHController::getSentPackageCount
unsigned int getSentPackageCount()
requests the number of sent packages. Request ist transferred to the serial interface that knows abou...
Definition: SVHController.cpp:767
driver_svh::SVHController::disconnect
void disconnect()
disconnect serial device
Definition: SVHController.cpp:138
driver_svh::SVHFingerManager::setCurrentSettings
bool setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
overwrite current parameters
Definition: SVHFingerManager.cpp:1074
SVHFingerManager.h
driver_svh::SVHFingerManager::setDefaultHomeSettings
void setDefaultHomeSettings()
initialize the homing settings with hardcoded defaults. These can be overwritten by the setHomeSettin...
Definition: SVHFingerManager.cpp:1216
driver_svh::SVHControllerFeedback::current
int16_t current
Returned current value of the motor [mA].
Definition: SVHControllerFeedback.h:50
driver_svh::SVHPositionSettings::wmx
float wmx
Reference signal maximum value.
Definition: SVHPositionSettings.h:50
driver_svh::SVHFingerManager::getDefaultCurrentSettings
std::vector< SVHCurrentSettings > getDefaultCurrentSettings()
get default current settings. These are either values previously set from calling software or hardcod...
Definition: SVHFingerManager.cpp:1254
driver_svh::SVHFingerManager::m_serial_device
std::string m_serial_device
m_serial_device Device handle of the device to use, is overwritten if connect is called with an argum...
Definition: SVHFingerManager.h:423
driver_svh::SVHCurrentSettings::wmx
float wmx
Reference signal maximum value.
Definition: SVHCurrentSettings.h:49
driver_svh::SVHFingerManager::resetDiagnosticData
bool resetDiagnosticData(const SVHChannel &channel)
resetDiagnosticData reset the diagnostic data vectors
Definition: SVHFingerManager.cpp:1173
driver_svh::SVHFingerManager::getCurrentSettings
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings)
returns actual current controller settings of channel
Definition: SVHFingerManager.cpp:986
driver_svh::SVHController::CHANNEL_EFFORT_CONSTANTS
static const float CHANNEL_EFFORT_CONSTANTS[9][2]
Effort multipliers to calculate the torque of the motors for the individual channels.
Definition: SVHController.h:258
driver_svh::SVHFingerManager::m_is_homed
std::vector< bool > m_is_homed
vector storing reset flags for each channel
Definition: SVHFingerManager.h:367
driver_svh::SVHFingerManager::disconnect
void disconnect()
disconnect SCHUNK five finger hand
Definition: SVHFingerManager.cpp:275
driver_svh::SVHHomeSettings::range_rad
float range_rad
Definition: SVHHomeSettings.h:62
driver_svh::SVHFingerManager::m_is_switched_off
std::vector< bool > m_is_switched_off
Definition: SVHFingerManager.h:371
driver_svh::SVHController::getControllerFeedback
bool getControllerFeedback(const SVHChannel &channel, SVHControllerFeedback &controller_feedback)
request the latest stored controllerfeedback (current, position) from the controller.
Definition: SVHController.cpp:697
driver_svh::SVHFingerManager::isEnabled
bool isEnabled(const SVHChannel &channel)
returns true, if current channel has been enabled
Definition: SVHFingerManager.cpp:912
driver_svh::SVHFingerManager::convertRad2Ticks
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...
Definition: SVHFingerManager.cpp:1427
driver_svh::SVHController::getFirmwareInfo
SVHFirmwareInfo getFirmwareInfo()
get the latest stored Firmware information from the controller (NOT THE HARDWARE)
Definition: SVHController.cpp:754
driver_svh::SVHController::m_channel_description
static const char * m_channel_description[]
Description values to get the corresponding string value to a channel enum.
Definition: SVHController.h:255
driver_svh::SVHFingerManager::setPositionSettings
bool setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
overwrite position parameters
Definition: SVHFingerManager.cpp:1111
SVH_LOG_ERROR_STREAM
#define SVH_LOG_ERROR_STREAM(NAME, M)
Definition: Logger.h:60
driver_svh::SVHHomeSettings::reset_current_factor
float reset_current_factor
Definition: SVHHomeSettings.h:66
driver_svh::SVHFingerManager::m_reset_order
std::vector< SVHChannel > m_reset_order
vector storing the reset order of the channels
Definition: SVHFingerManager.h:426
driver_svh::SVHFingerManager::convertmAtoN
double convertmAtoN(const SVHChannel &channel, const int16_t &current)
Converts joint currents of a specific channel from current [mA] to force [N] factoring the effort_con...
Definition: SVHFingerManager.cpp:1482
driver_svh::SVH_ALL
@ SVH_ALL
Definition: SVHController.h:67
driver_svh::SVH_FINGER_SPREAD
@ SVH_FINGER_SPREAD
Definition: SVHController.h:76
driver_svh::SVHFingerManager::m_ticks2rad
std::vector< double > m_ticks2rad
position conversion factor (ticks to RAD) for each channel
Definition: SVHFingerManager.h:355
driver_svh::SVHFingerManager::isInsideBounds
bool isInsideBounds(const SVHChannel &channel, const int32_t &target_position)
Check bounds of target positions.
Definition: SVHFingerManager.cpp:1494
driver_svh::SVHController::getPositionSettings
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
request the latest stored positionsettings from the controller
Definition: SVHController.cpp:720
driver_svh::SVHController::resetPackageCounts
void resetPackageCounts()
resetPackageCounts sets the sent and reveived package counts to zero
Definition: SVHController.cpp:759
driver_svh::SVHController::setPositionSettings
void setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
activate a new set of position controller settings for a specific channel
Definition: SVHController.cpp:417
driver_svh::SVHFingerManager::convertTicks2Rad
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...
Definition: SVHFingerManager.cpp:1444
driver_svh::SVH_DIMENSION
@ SVH_DIMENSION
Definition: SVHController.h:77
driver_svh::SVHFingerManager::m_homing_timeout
std::chrono::seconds m_homing_timeout
Timeout for homing.
Definition: SVHFingerManager.h:348
driver_svh::SVHHomeSettings::minimum_offset
float minimum_offset
Minimum reachable tick limit, given as offset from the hard stop (soft limit)
Definition: SVHHomeSettings.h:49
driver_svh::SVH_MIDDLE_FINGER_PROXIMAL
@ SVH_MIDDLE_FINGER_PROXIMAL
Definition: SVHController.h:73
driver_svh::SVHFingerManager::getDiagnosticStatus
bool getDiagnosticStatus(const SVHChannel &channel, struct DiagnosticState &diagnostic_status)
returns actual diagnostic status of channel
Definition: SVHFingerManager.cpp:610
driver_svh::SVHFingerManager::m_diagnostic_position_maximum
std::vector< double > m_diagnostic_position_maximum
vectors storing diagnostic information, position maximum
Definition: SVHFingerManager.h:386
driver_svh
Definition: SVHControlCommand.h:39
driver_svh::SVHController
This class controls the the SCHUNK five finger hand.
Definition: SVHController.h:87
driver_svh::SVHFingerManager::getPositionSettings
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
returns actual position controller settings of channel
Definition: SVHFingerManager.cpp:1002
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_current_maximum
double diagnostic_current_maximum
Definition: SVHFingerManager.h:78
driver_svh::SVHController::isEnabled
bool isEnabled(const SVHChannel &channel)
Check if a channel was enabled.
Definition: SVHController.cpp:787
driver_svh::SVHFingerManager::m_diagnostic_current_maximum
std::vector< double > m_diagnostic_current_maximum
vectors storing diagnostic information, current maximum
Definition: SVHFingerManager.h:380
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_current_minimum
double diagnostic_current_minimum
Definition: SVHFingerManager.h:79
driver_svh::SVHController::requestControllerFeedback
void requestControllerFeedback(const SVHChannel &channel)
request feedback (position and current) to a specific channel
Definition: SVHController.cpp:380
driver_svh::SVH_PINKY
@ SVH_PINKY
Definition: SVHController.h:75
driver_svh::SVHController::disableChannel
void disableChannel(const SVHChannel &channel)
Disable one or all motor channels.
Definition: SVHController.cpp:313
driver_svh::SVHPositionSettings::dwmx
float dwmx
Reference signal delta maximum threshold.
Definition: SVHPositionSettings.h:52
driver_svh::SVHFingerManager::m_diagnostic_deadlock
std::vector< double > m_diagnostic_deadlock
vectors storing diagnostic information, diagnostics deadlock
Definition: SVHFingerManager.h:392
driver_svh::SVHFingerManager::getFirmwareInfo
SVHFirmwareInfo getFirmwareInfo(const std::string &dev_name="/dev/ttyUSB0", const unsigned int &retry_count=3)
getFirmwareInfo Requests the firmware information from the harware, waits a bit and returns the last ...
Definition: SVHFingerManager.cpp:1565
driver_svh::SVHFingerManager::m_current_settings
std::vector< SVHCurrentSettings > m_current_settings
Vector of current controller parameters for each finger (as given by external config)
Definition: SVHFingerManager.h:401
driver_svh::SVHFingerManager::m_controller
SVHController * m_controller
pointer to svh controller
Definition: SVHFingerManager.h:332
driver_svh::SVHFingerManager::resetChannel
bool resetChannel(const SVHChannel &channel)
reset function for channel
Definition: SVHFingerManager.cpp:298
driver_svh::SVHFingerManager::m_connected
bool m_connected
holds the connected state
Definition: SVHFingerManager.h:341
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_deadlock
double diagnostic_deadlock
Definition: SVHFingerManager.h:82
driver_svh::SVHHomeSettings::maximum_offset
float maximum_offset
Maximum reachable tick limit, given as an offset from the hard stop (soft limit)
Definition: SVHHomeSettings.h:51
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_motor_state
bool diagnostic_motor_state
Definition: SVHFingerManager.h:77
driver_svh::SVHFingerManager::m_position_settings_given
std::vector< bool > m_position_settings_given
Definition: SVHFingerManager.h:411
driver_svh::SVHFingerManager::m_position_settings
std::vector< SVHPositionSettings > m_position_settings
Vector of position controller parameters for each finger (as given by external config)
Definition: SVHFingerManager.h:408
driver_svh::SVHController::connect
bool connect(const std::string &dev_name)
Open serial device connection.
Definition: SVHController.cpp:121
Logger.h
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_position_maximum
double diagnostic_position_maximum
Definition: SVHFingerManager.h:80
driver_svh::SVHFingerManager::isConnected
bool isConnected()
returns connected state of finger manager
Definition: SVHFingerManager.h:111
driver_svh::SVHCurrentSettings
The SVHCurrentSettings save the current controller paramters for a single motor.
Definition: SVHCurrentSettings.h:44
driver_svh::SVHFingerManager::m_reset_speed_factor
float m_reset_speed_factor
Factor for determining the finger speed during reset. Only 0.0-1.0 is allowed.
Definition: SVHFingerManager.h:395
driver_svh::SVHFingerManager::~SVHFingerManager
virtual ~SVHFingerManager()
Definition: SVHFingerManager.cpp:120
driver_svh::SVHFingerManager::m_poll_feedback
std::atomic< bool > m_poll_feedback
Flag whether to poll feedback periodically in the feedback thread.
Definition: SVHFingerManager.h:335
driver_svh::SVHFirmwareInfo
The SVHFirmwareInfo holds the data of a firmware response from the hardware.
Definition: SVHFirmwareInfo.h:48
driver_svh::SVHControllerFeedback
The SVHControllerFeedback saves the feedback of a single motor.
Definition: SVHControllerFeedback.h:45
driver_svh::SVHFingerManager::m_diagnostic_current_state
std::vector< bool > m_diagnostic_current_state
vectors storing diagnostic information, current state
Definition: SVHFingerManager.h:377
driver_svh::SVHFingerManager::m_current_settings_given
std::vector< bool > m_current_settings_given
Definition: SVHFingerManager.h:405
driver_svh::SVHHomeSettings::idle_position
float idle_position
Definition: SVHHomeSettings.h:54
driver_svh::SVHFingerManager::setMaxForce
bool setMaxForce(float max_force)
setMaxForce set the max force / current as a persentage of the maximum possible current
Definition: SVHFingerManager.cpp:1526
driver_svh::SVHCurrentSettings::wmn
float wmn
Reference signal minimum value.
Definition: SVHCurrentSettings.h:47
driver_svh::SVHFingerManager::getCurrent
bool getCurrent(const SVHChannel &channel, double &current)
returns current value of channel
Definition: SVHFingerManager.cpp:754
driver_svh::SVHController::setControllerTargetAllChannels
void setControllerTargetAllChannels(const std::vector< int32_t > &positions)
Setting new position controller target for all fingers.
Definition: SVHController.cpp:185
driver_svh::SVHFingerManager::getHomeSettings
bool getHomeSettings(const SVHChannel &channel, SVHHomeSettings &home_settings)
returns actual home settings of channel
Definition: SVHFingerManager.cpp:1018
driver_svh::SVHFingerManager::m_position_max
std::vector< int32_t > m_position_max
max position vector for each channel
Definition: SVHFingerManager.h:361
SVH_LOG_WARN_STREAM
#define SVH_LOG_WARN_STREAM(NAME, M)
Definition: Logger.h:53
driver_svh::SVHHomeSettings
data sctructure for home positions
Definition: SVHHomeSettings.h:44
driver_svh::SVHController::getReceivedPackageCount
unsigned int getReceivedPackageCount()
request the number of correctly received packages. This number is refreshed every time the serialinte...
Definition: SVHController.cpp:782
driver_svh::SVHFingerManager::requestControllerFeedback
bool requestControllerFeedback(const SVHChannel &channel)
send request controller feedback paket
Definition: SVHFingerManager.cpp:699
driver_svh::SVHChannel
SVHChannel
Definition: SVHController.h:65
driver_svh::SVHFirmwareInfo::version_minor
uint16_t version_minor
Minor version number.
Definition: SVHFirmwareInfo.h:55
driver_svh::SVH_RING_FINGER
@ SVH_RING_FINGER
Definition: SVHController.h:74
driver_svh::SVHFingerManager::m_diagnostic_current_minimum
std::vector< double > m_diagnostic_current_minimum
vectors storing diagnostic information, current minimum
Definition: SVHFingerManager.h:383
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_encoder_state
bool diagnostic_encoder_state
Definition: SVHFingerManager.h:76
driver_svh::SVHController::setControllerTarget
void setControllerTarget(const SVHChannel &channel, const int32_t &position)
Set new position target for finger index.
Definition: SVHController.cpp:156
driver_svh::SVHPositionSettings::wmn
float wmn
Reference signal minimum value.
Definition: SVHPositionSettings.h:48
driver_svh::SVHFingerManager::SVHFingerManager
SVHFingerManager(const std::vector< bool > &disable_mask=std::vector< bool >(9, false), const uint32_t &reset_timeout=5)
Definition: SVHFingerManager.cpp:52
driver_svh::SVHFingerManager::setResetTimeout
void setResetTimeout(const int &reset_timeout)
setResetTimeout Helper function to set the timout durind rest of fingers
Definition: SVHFingerManager.cpp:1520
driver_svh::SVHController::requestFirmwareInfo
void requestFirmwareInfo()
request a transmission of formware information
Definition: SVHController.cpp:539
driver_svh::SVHFingerManager::m_position_home
std::vector< int32_t > m_position_home
home position after complete reset of each channel
Definition: SVHFingerManager.h:364
driver_svh::SVHFingerManager::m_max_current_percentage
float m_max_current_percentage
limit the maximum of the force / current of the finger as a percentage of the possible maximum
Definition: SVHFingerManager.h:352
driver_svh::SVHFingerManager::m_diagnostic_position_minimum
std::vector< double > m_diagnostic_position_minimum
vectors storing diagnostic information, position minimum
Definition: SVHFingerManager.h:389
driver_svh::SVHFingerManager::setTargetPosition
bool setTargetPosition(const SVHChannel &channel, double position, double current)
set target position of a channel
Definition: SVHFingerManager.cpp:837
driver_svh::SVHFingerManager::requestControllerState
void requestControllerState()
Definition: SVHFingerManager.cpp:1515
driver_svh::SVHFingerManager::getPosition
bool getPosition(const SVHChannel &channel, double &position)
returns position value of channel (will not acces hardware but return latest value)
Definition: SVHFingerManager.cpp:714
driver_svh::SVHFingerManager::setResetSpeed
void setResetSpeed(const float &speed)
setResetSpeed Set the speed percentage during reset
Definition: SVHFingerManager.cpp:1411
driver_svh::SVH_THUMB_FLEXION
@ SVH_THUMB_FLEXION
Definition: SVHController.h:68
driver_svh::SVHFingerManager::setForceLimit
float setForceLimit(const SVHChannel &channel, float force_limit)
setForceLimit set the force limit for the given channel
Definition: SVHFingerManager.cpp:1542
driver_svh::SVHControllerFeedback::position
int32_t position
Returned position value of the motor [Ticks].
Definition: SVHControllerFeedback.h:48
driver_svh::SVHFingerManager::DiagnosticState
Definition: SVHFingerManager.h:74
driver_svh::SVHFingerManager::enableChannel
bool enableChannel(const SVHChannel &channel)
enable controller of channel
Definition: SVHFingerManager.cpp:635
driver_svh::SVHFingerManager::m_home_settings
std::vector< SVHHomeSettings > m_home_settings
Vector of home settings for each finger (as given by external config)
Definition: SVHFingerManager.h:414
driver_svh::SVHFingerManager::DiagnosticState::diagnostic_position_minimum
double diagnostic_position_minimum
Definition: SVHFingerManager.h:81
driver_svh::SVHHomeSettings::direction
int direction
Movement direction of the finger +1 or -1 home in positive or negative direction.
Definition: SVHHomeSettings.h:47
driver_svh::SVHPositionSettings
The SVHPositionSettings save the position controller paramters for a single motor.
Definition: SVHPositionSettings.h:44
driver_svh::SVH_MIDDLE_FINGER_DISTAL
@ SVH_MIDDLE_FINGER_DISTAL
Definition: SVHController.h:72
driver_svh::SVHFirmwareInfo::version_major
uint16_t version_major
Major version number.
Definition: SVHFirmwareInfo.h:53
driver_svh::SVHController::enableChannel
void enableChannel(const SVHChannel &channel)
Enable one or all motor channels.
Definition: SVHController.cpp:218
driver_svh::SVHFingerManager::m_reset_timeout
std::chrono::seconds m_reset_timeout
Time in seconds after which the a reset is aborted if no change in current is observable.
Definition: SVHFingerManager.h:398
driver_svh::SVHFingerManager::m_diagnostic_encoder_state
std::vector< bool > m_diagnostic_encoder_state
vectors storing diagnostic information, encoder state
Definition: SVHFingerManager.h:374
driver_svh::SVH_THUMB_OPPOSITION
@ SVH_THUMB_OPPOSITION
Definition: SVHController.h:69
driver_svh::SVHFingerManager::getDefaultPositionSettings
std::vector< SVHPositionSettings > getDefaultPositionSettings(const bool &reset=false)
get default position settings. These are either values previously set from calling software or hardco...
Definition: SVHFingerManager.cpp:1316
driver_svh::SVH_INDEX_FINGER_DISTAL
@ SVH_INDEX_FINGER_DISTAL
Definition: SVHController.h:70
driver_svh::SVHFingerManager::isHomed
bool isHomed(const SVHChannel &channel)
returns true, if current channel has been resetted
Definition: SVHFingerManager.cpp:953
driver_svh::SVHFingerManager::connect
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.
Definition: SVHFingerManager.cpp:134
driver_svh::SVHFingerManager::currentSettingsAreSafe
bool currentSettingsAreSafe(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
currentSettingsAreSafe helper function to check for the most important values of the current settings
Definition: SVHFingerManager.cpp:1033
driver_svh::SVHFingerManager::m_position_min
std::vector< int32_t > m_position_min
min position vector for each channel
Definition: SVHFingerManager.h:358
driver_svh::SVHController::setCurrentSettings
void setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
activate a new set of current controller settings for a specific channel
Definition: SVHController.cpp:474
SVH_LOG_INFO_STREAM
#define SVH_LOG_INFO_STREAM(NAME, M)
Definition: Logger.h:46
driver_svh::SVHFingerManager::m_firmware_info
SVHFirmwareInfo m_firmware_info
Firmware info of the connected Hand.
Definition: SVHFingerManager.h:417
driver_svh::SVHFingerManager::m_connection_feedback_given
bool m_connection_feedback_given
Definition: SVHFingerManager.h:345
driver_svh::SVHFingerManager::setAllTargetPositions
bool setAllTargetPositions(const std::vector< double > &positions)
set all target positions at once
Definition: SVHFingerManager.cpp:771
SVH_LOG_DEBUG_STREAM
#define SVH_LOG_DEBUG_STREAM(NAME, M)
Definition: Logger.h:39
driver_svh::SVHFingerManager::pollFeedback
void pollFeedback()
Periodically poll feedback from the hardware.
Definition: SVHFingerManager.cpp:1627
driver_svh::SVH_INDEX_FINGER_PROXIMAL
@ SVH_INDEX_FINGER_PROXIMAL
Definition: SVHController.h:71
driver_svh::SVHFingerManager::m_feedback_thread
std::thread m_feedback_thread
Thread for polling periodic feedback from the hardware.
Definition: SVHFingerManager.h:338


schunk_svh_library
Author(s): Georg Heppner, Lars Pfotzer, Felix Exner, Johannes Mangler, Stefan Scherzinger, Pascal Becker
autogenerated on Fri Apr 14 2023 02:53:52