SVHController.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 //----------------------------------------------------------------------
45 //----------------------------------------------------------------------
47 
48 #include <chrono>
49 #include <functional>
52 #include <thread>
53 
55 
56 namespace driver_svh {
57 
58 
60 const char* SVHController::m_channel_description[] = {"Thumb_Flexion",
61  "Thumb_Opposition", // wrist
62  "Index_Finger_Distal",
63  "Index_Finger_Proximal",
64  "Middle_Finger_Distal",
65  "Middle_Finger_Proximal",
66  "Ring_Finger",
67  "Pinky",
68  "Finger_Spread",
69  NULL};
70 
72 const float SVHController::CHANNEL_EFFORT_CONSTANTS[][2] = {
73  // a, b // y = a*x + b with y = effort and x = current
74  0.015,
75  -1.543, // Thumb Flexion
76  0,
77  0, // Thumb Opposition
78  0.014,
79  -0.07, // Index Finger Distal
80  0.015,
81  0.282, // Index Finger Proximal
82  0.014,
83  -0.026, // Middle Finger Distal
84  0.015,
85  0.336, // Middle Finger Proximal
86  0.007,
87  -0.073, // Ring Finger
88  0.005,
89  0.081, // Pinky
90  0,
91  0 // Finger Spread
92 };
93 
95  : m_current_settings(SVH_DIMENSION)
96  , // Vectors have to be filled with objects for correct deserialization
97  m_position_settings(SVH_DIMENSION)
98  , m_controller_feedback(SVH_DIMENSION)
99  , m_serial_interface(new SVHSerialInterface(std::bind(
100  &SVHController::receivedPacketCallback, this, std::placeholders::_1, std::placeholders::_2)))
101  , m_enable_mask(0)
102  , m_received_package_count(0)
103 {
104  SVH_LOG_DEBUG_STREAM("SVHController", "SVH Controller started");
107 }
108 
110 {
111  if (m_serial_interface != NULL)
112  {
113  disconnect();
114  delete m_serial_interface;
115  m_serial_interface = NULL;
116  }
117 
118  SVH_LOG_DEBUG_STREAM("SVHController", "SVH Controller terminated");
119 }
120 
121 bool SVHController::connect(const std::string& dev_name)
122 {
123  SVH_LOG_DEBUG_STREAM("SVHController", "Connect was called, starting the serial interface...");
124  if (m_serial_interface != NULL)
125  {
126  bool success = m_serial_interface->connect(dev_name);
127  SVH_LOG_DEBUG_STREAM("SVHController",
128  "Connect finished " << ((success) ? "succesfully" : "with an error"));
129  return success;
130  }
131  else
132  {
133  SVH_LOG_DEBUG_STREAM("SVHController", "Connect failed");
134  return false;
135  }
136 }
137 
139 {
140  SVH_LOG_DEBUG_STREAM("SVHController",
141  "Disconnect called, disabling all channels and closing interface...");
143  {
144  // Disable all channels
147  }
148  // Reset the Firmware version, so we get always the current version on a reconnect or 0.0 on
149  // failure
152 
153  SVH_LOG_DEBUG_STREAM("SVHController", "Disconnect finished");
154 }
155 
156 void SVHController::setControllerTarget(const SVHChannel& channel, const int32_t& position)
157 {
158  // No Sanity Checks for out of bounds positions at this point as the finger manager has already
159  // handled these
160  if ((channel != SVH_ALL) && (channel >= 0 && channel < SVH_DIMENSION))
161  {
162  // The channel is encoded in the index byte
163  SVHSerialPacket serial_packet(0, SVH_SET_CONTROL_COMMAND | static_cast<uint8_t>(channel << 4));
164  SVHControlCommand control_command(position);
165  // Note the 40 byte ArrayBuilder initialization -> this is needed to get a zero padding in the
166  // serialpacket. Otherwise it would be shorter
167  ArrayBuilder ab(40);
168  ab << control_command;
169  serial_packet.data = ab.array;
170  m_serial_interface->sendPacket(serial_packet);
171 
172  // Debug Disabled as it is way to noisy
173  SVH_LOG_DEBUG_STREAM("SVHController",
174  "Control command was given for channel: "
175  << channel << "Driving motor to position: " << position);
176  }
177  else
178  {
179  SVH_LOG_WARN_STREAM("SVHController",
180  "Control command was given for unknown (or all) channel: "
181  << channel << "- ignoring request");
182  }
183 }
184 
185 void SVHController::setControllerTargetAllChannels(const std::vector<int32_t>& positions)
186 {
187  if (positions.size() >= SVH_DIMENSION)
188  {
190  SVHControlCommandAllChannels control_command(positions);
191  ArrayBuilder ab(40);
192  ab << control_command;
193  serial_packet.data = ab.array;
194  m_serial_interface->sendPacket(serial_packet);
195 
196  // Debug Disabled as it is way to noisy
197  SVH_LOG_DEBUG_STREAM("SVHController",
198  "Control command was given for all channels: Driving motors to positions: "
199  << positions[0] << " , " << positions[1] << " , " << positions[2]
200  << " , " << positions[3] << " , " << positions[4] << " , "
201  << positions[5] << " , " << positions[6] << " , " << positions[7]
202  << " , " << positions[8] << " , ");
203  }
204  // We could theoretically allow fewer channels but this leaves some questions. Are the given
205  // channels in right order? was it realy intented to just give fewer positions? What to do with
206  // the ones that did not get anything? Just disallowing it seems to be the most understandable
207  // decision.
208  else
209  {
211  "SVHController",
212  "Control command was given for all channels but with to few points. Expected at least "
213  << SVH_DIMENSION << " values but only got " << positions.size()
214  << "use the individual setTarget function for this");
215  }
216 }
217 
219 {
220  SVHSerialPacket serial_packet(0, SVH_SET_CONTROLLER_STATE);
221  SVHControllerState controller_state;
222  ArrayBuilder ab(40);
223 
224  SVH_LOG_DEBUG_STREAM("SVHController", "Enable of channel " << channel << " requested.");
225 
226  // In case no channel was enabled we need to enable the 12V dc drivers first
227  if (m_enable_mask == 0)
228  {
229  SVH_LOG_DEBUG_STREAM("SVHController",
230  "Enable was called and no channel was previously activated, commands are "
231  "sent individually......");
232  SVH_LOG_DEBUG_STREAM("SVHController",
233  "Sending pwm_fault and pwm_otw...(0x001F) to reset software warnings");
234  // Reset faults and overtemperature warnings saved in the controller
235  controller_state.pwm_fault = 0x001F;
236  controller_state.pwm_otw = 0x001F;
237  ab << controller_state;
238  serial_packet.data = ab.array;
239  m_serial_interface->sendPacket(serial_packet);
240  ab.reset(40);
241 
242  // Small delays seem to make communication at this point more reliable although they SHOULD NOT
243  // be necessary
244  std::this_thread::sleep_for(std::chrono::microseconds(2000));
245 
246  SVH_LOG_DEBUG_STREAM("SVHController",
247  "Enabling 12V Driver (pwm_reset and pwm_active = 0x0200)...");
248  // enable +12v supply driver
249  controller_state.pwm_reset = 0x0200;
250  controller_state.pwm_active = 0x0200;
251  ab << controller_state;
252  serial_packet.data = ab.array;
253  m_serial_interface->sendPacket(serial_packet);
254  ab.reset(40);
255 
256  std::this_thread::sleep_for(std::chrono::microseconds(2000));
257 
258  SVH_LOG_DEBUG_STREAM("SVHController", "Enabling pos_ctrl and cur_ctrl...");
259  // enable controller
260  controller_state.pos_ctrl = 0x0001;
261  controller_state.cur_ctrl = 0x0001;
262  ab << controller_state;
263  serial_packet.data = ab.array;
264  m_serial_interface->sendPacket(serial_packet);
265  ab.reset(40);
266 
267  std::this_thread::sleep_for(std::chrono::microseconds(2000));
268 
269  SVH_LOG_DEBUG_STREAM("SVHController", "...Done");
270  }
271 
272  // enable actual channels (again we only accept individual channels for safety)
273  if (channel >= 0 && channel < SVH_DIMENSION)
274  {
275  SVH_LOG_DEBUG_STREAM("SVHController", "Enabling motor: " << channel);
276  // oring all channels to create the activation mask-> high = channel active
277  m_enable_mask |= (1 << channel);
278 
279  // SENDING EVERYTHING AT ONCE WILL LEAD TO "Jumping" behaviour of the controller on faster
280  // Systems ---> this has to do with the initialization of the hardware controllers. If we split
281  // it in two calls we will reset them first and then activate making sure that all values are
282  // initialized properly effectively preventing any jumping behaviour
283  ab.reset(40);
284  controller_state.pwm_fault = 0x001F;
285  controller_state.pwm_otw = 0x001F;
286  controller_state.pwm_reset = (0x0200 | (m_enable_mask & 0x01FF));
287  controller_state.pwm_active = (0x0200 | (m_enable_mask & 0x01FF));
288  ab << controller_state;
289  serial_packet.data = ab.array;
290  m_serial_interface->sendPacket(serial_packet);
291  ab.reset(40);
292 
293  // WARNING: DO NOT ! REMOVE THESE DELAYS OR THE HARDWARE WILL! FREAK OUT! (see reason above)
294  std::this_thread::sleep_for(std::chrono::microseconds(500));
295 
296  controller_state.pos_ctrl = 0x0001;
297  controller_state.cur_ctrl = 0x0001;
298  ab << controller_state;
299  serial_packet.data = ab.array;
300  m_serial_interface->sendPacket(serial_packet);
301  ab.reset(40);
302 
303  SVH_LOG_DEBUG_STREAM("SVHController", "Enabled channel: " << channel);
304  }
305  else
306  {
307  SVH_LOG_ERROR_STREAM("SVHController",
308  "Activation request for ALL or unknown channel: " << channel
309  << "- ignoring request");
310  }
311 }
312 
314 {
315  SVH_LOG_DEBUG_STREAM("SVHController", "Disable of channel " << channel << " requested.");
316 
318  {
319  // prepare general packet
320  SVHSerialPacket serial_packet(0, SVH_SET_CONTROLLER_STATE);
321  SVHControllerState controller_state;
322  ArrayBuilder ab(40);
323 
324  // we just accept it at this point because it makes no difference in the calls
325  if (channel == SVH_ALL)
326  {
327  m_enable_mask = 0;
328  controller_state.pwm_fault = 0x001F;
329  controller_state.pwm_otw = 0x001F;
330 
331  // default initialization to zero -> controllers are deactivated
332  ab << controller_state;
333  serial_packet.data = ab.array;
334  m_serial_interface->sendPacket(serial_packet);
335 
336  SVH_LOG_DEBUG_STREAM("SVHController", "Disabled all channels");
337  }
338  else if (channel >= 0 && channel < SVH_DIMENSION)
339  {
340  controller_state.pwm_fault = 0x001F;
341  controller_state.pwm_otw = 0x001F;
342  // Disable the finger in the bitmask
343  m_enable_mask &= ~(1 << channel);
344 
345  if (m_enable_mask != 0) // pos and current control stay on then
346  {
347  controller_state.pwm_reset = (0x0200 | (m_enable_mask & 0x01FF));
348  controller_state.pwm_active = (0x0200 | (m_enable_mask & 0x01FF));
349  controller_state.pos_ctrl = 0x0001;
350  controller_state.cur_ctrl = 0x0001;
351  }
352 
353  ab << controller_state;
354  serial_packet.data = ab.array;
355  m_serial_interface->sendPacket(serial_packet);
356 
357  SVH_LOG_DEBUG_STREAM("SVHController", "Disabled channel: " << channel);
358  }
359  else
360  {
361  SVH_LOG_WARN_STREAM("SVHController",
362  "Disable was requestet for unknown channel: " << channel
363  << "- ignoring request");
364  }
365  }
366  else
367  {
368  SVH_LOG_ERROR_STREAM("SVHController",
369  "Disabling Channel not possible. Serial interface is not connected!");
370  }
371 }
372 
374 {
375  SVH_LOG_DEBUG_STREAM("SVHController", "Requesting ControllerStatefrom Hardware");
376  SVHSerialPacket serial_packet(40, SVH_GET_CONTROLLER_STATE);
377  m_serial_interface->sendPacket(serial_packet);
378 }
379 
381 {
382  if ((channel != SVH_ALL) && (channel >= 0 && channel < SVH_DIMENSION))
383  {
384  SVHSerialPacket serial_packet(40,
385  SVH_GET_CONTROL_FEEDBACK | static_cast<uint8_t>(channel << 4));
386  m_serial_interface->sendPacket(serial_packet);
387 
388  // Disabled as it spams the output to much
389  SVH_LOG_DEBUG_STREAM("SVHController",
390  "Controller feedback was requested for channel: " << channel);
391  }
392  else if (channel == SVH_ALL)
393  {
395  m_serial_interface->sendPacket(serial_packet);
396 
397  // Disabled as it spams the output to much
398  SVH_LOG_DEBUG_STREAM("SVHController", "Controller feedback was requested for all channels ");
399  }
400  else
401  {
403  "SVHController",
404  "Controller feedback was requestet for unknown channel: " << channel << "- ignoring request");
405  }
406 }
407 
409 {
410  SVH_LOG_DEBUG_STREAM("SVHController",
411  "Requesting PositionSettings from Hardware for channel: " << channel);
412  SVHSerialPacket serial_packet(40,
413  (SVH_GET_POSITION_SETTINGS | static_cast<uint8_t>(channel << 4)));
414  m_serial_interface->sendPacket(serial_packet);
415 }
416 
418  const SVHPositionSettings& position_settings)
419 {
420  if ((channel != SVH_ALL) && (channel >= 0 && channel < SVH_DIMENSION))
421  {
422  SVHSerialPacket serial_packet(0,
423  SVH_SET_POSITION_SETTINGS | static_cast<uint8_t>(channel << 4));
424  ArrayBuilder ab;
425  ab << position_settings;
426  serial_packet.data = ab.array;
427  m_serial_interface->sendPacket(serial_packet);
428 
429  // Save already in case we dont get immediate response
430  m_position_settings[channel] = position_settings;
431 
432  SVH_LOG_DEBUG_STREAM("SVHController",
433  "Position controller settings where send to change channel: " << channel
434  << " : ");
435  SVH_LOG_DEBUG_STREAM("SVHController",
436  "wmn " << position_settings.wmn << " "
437  << "wmx " << position_settings.wmx << " "
438  << "dwmx " << position_settings.dwmx << " "
439  << "ky " << position_settings.ky << " "
440  << "dt " << position_settings.dt << " "
441  << "imn " << position_settings.imn << " "
442  << "imx " << position_settings.imx << " "
443  << "kp " << position_settings.kp << " "
444  << "ki " << position_settings.ki << " "
445  << "kd " << position_settings.kd << " ");
446  }
447  else
448  {
449  SVH_LOG_WARN_STREAM("SVHController",
450  "Position controller settings where given for unknown channel: "
451  << channel << "- ignoring request");
452  }
453 }
454 
456 {
457  SVH_LOG_DEBUG_STREAM("SVHController", "Requesting CurrentSettings for channel: " << channel);
458 
459  if ((channel != SVH_ALL) && (channel >= 0 && channel < SVH_DIMENSION))
460  {
461  SVHSerialPacket serial_packet(40,
462  (SVH_GET_CURRENT_SETTINGS | static_cast<uint8_t>(channel << 4)));
463  m_serial_interface->sendPacket(serial_packet);
464  }
465  else
466  {
468  "SVHController",
469  "Get Current Settings can only be requested with a specific channel, ALL or unknown channel:"
470  << channel << "was selected ");
471  }
472 }
473 
475  const SVHCurrentSettings& current_settings)
476 {
477  if ((channel != SVH_ALL) && (channel >= 0 && channel < SVH_DIMENSION))
478  {
479  SVHSerialPacket serial_packet(0, SVH_SET_CURRENT_SETTINGS | static_cast<uint8_t>(channel << 4));
480  ArrayBuilder ab;
481  ab << current_settings;
482  serial_packet.data = ab.array;
483  m_serial_interface->sendPacket(serial_packet);
484 
485  // Save already in case we dont get immediate response
486  m_current_settings[channel] = current_settings;
487 
488  SVH_LOG_DEBUG_STREAM("SVHController",
489  "Current controller settings where send to change channel: " << channel
490  << " : ");
491  SVH_LOG_DEBUG_STREAM("SVHController",
492  "wmn " << current_settings.wmn << " "
493  << "wmx " << current_settings.wmx << " "
494  << "ky " << current_settings.ky << " "
495  << "dt " << current_settings.dt << " "
496  << "imn " << current_settings.imn << " "
497  << "imx " << current_settings.imx << " "
498  << "kp " << current_settings.kp << " "
499  << "ki " << current_settings.ki << " "
500  << "umn " << current_settings.umn << " "
501  << "umx " << current_settings.umx);
502  }
503  else
504  {
505  SVH_LOG_WARN_STREAM("SVHController",
506  "Current controller settings where given for unknown channel: "
507  << channel << "- ignoring request");
508  }
509 }
510 
512 {
513  SVH_LOG_DEBUG_STREAM("SVHController", "Requesting EncoderValues from hardware");
514  SVHSerialPacket serial_packet(40, SVH_GET_ENCODER_VALUES);
515  m_serial_interface->sendPacket(serial_packet);
516 }
517 
519 {
520  SVH_LOG_DEBUG_STREAM("SVHController", "Setting new Encoder values : ");
521  for (size_t i = 0; i < encoder_settings.scalings.size(); i++)
522  {
523  // log stream unfortunately does not support the standard to stream operators yet
524  SVH_LOG_DEBUG_STREAM("SVHController",
525  "[" << (int)i << "] "
526  << ": " << encoder_settings.scalings[i] << " ");
527  }
528 
529  SVHSerialPacket serial_packet(0, SVH_SET_ENCODER_VALUES);
530  ArrayBuilder ab;
531  ab << encoder_settings;
532  serial_packet.data = ab.array;
533  m_serial_interface->sendPacket(serial_packet);
534 
535  // Save already in case we dont get imediate response
536  m_encoder_settings = encoder_settings;
537 }
538 
540 {
541  SVH_LOG_DEBUG_STREAM("SVHController", "Requesting firmware Information from hardware");
542 
543  SVHSerialPacket serial_packet(40, SVH_GET_FIRMWARE_INFO);
544  m_serial_interface->sendPacket(serial_packet);
545 }
546 
547 void SVHController::receivedPacketCallback(const SVHSerialPacket& packet, unsigned int packet_count)
548 {
549  // Extract Channel
550  uint8_t channel = (packet.address >> 4) & 0x0F;
551  // Prepare Data for conversion
552  ArrayBuilder ab;
553  ab.appendWithoutConversion(packet.data);
554 
556 
557  m_received_package_count = packet_count;
558 
559  // Packet meaning is encoded in the lower nibble of the adress byte
560  switch (packet.address & 0x0F)
561  {
564  if (channel >= 0 && channel < SVH_DIMENSION)
565  {
566  // std::cout << "Recieved: Controllerfeedback RAW Data: " << ab;
567  ab >> m_controller_feedback[channel];
568  // Disabled as this is spamming the output to much
569  SVH_LOG_DEBUG_STREAM("SVHController",
570  "Received a Control Feedback/Control Command packet for channel "
571  << channel
572  << " Position: " << (int)m_controller_feedback[channel].position
573  << " Current: " << (int)m_controller_feedback[channel].current);
574  }
575  else
576  {
578  "SVHController",
579  "Received a Control Feedback/Control Command packet for ILLEGAL channel "
580  << channel << "- packet ignored!");
581  }
582  break;
585  // We cannot just read them all into the vector (which would have been nice) because the
586  // feedback of all channels is structured different from the feedback of one channel. So the
587  // SVHControllerFeedbackAllChannels is used as an intermediary ( handles the deserialization)
588  ab >> feedback_all;
589  m_controller_feedback = feedback_all.feedbacks;
590  // Disabled as this is spannimg the output to much
592  "SVHController",
593  "Received a Control Feedback/Control Command packet for channel all channels ");
594  break;
597  if (channel >= 0 && channel < SVH_DIMENSION)
598  {
599  // std::cout << "Recieved: Postitionsettings RAW Data: " << ab; // for really intensive
600  // debugging
601  ab >> m_position_settings[channel];
602  SVH_LOG_DEBUG_STREAM("SVHController",
603  "Received a get/set position setting packet for channel " << channel);
604  SVH_LOG_DEBUG_STREAM("SVHController",
605  "wmn " << m_position_settings[channel].wmn << " "
606  << "wmx " << m_position_settings[channel].wmx << " "
607  << "dwmx " << m_position_settings[channel].dwmx << " "
608  << "ky " << m_position_settings[channel].ky << " "
609  << "dt " << m_position_settings[channel].dt << " "
610  << "imn " << m_position_settings[channel].imn << " "
611  << "imx " << m_position_settings[channel].imx << " "
612  << "kp " << m_position_settings[channel].kp << " "
613  << "ki " << m_position_settings[channel].ki << " "
614  << "kd " << m_position_settings[channel].kd);
615  }
616  else
617  {
618  SVH_LOG_ERROR_STREAM("SVHController",
619  "Received a get/set position setting packet for ILLEGAL channel "
620  << channel << "- packet ignored!");
621  }
622  break;
625  if (channel >= 0 && channel < SVH_DIMENSION)
626  {
627  // std::cout << "Recieved: Current Settings RAW Data: " << ab; // for really intensive
628  // debugging
629  ab >> m_current_settings[channel];
630  SVH_LOG_DEBUG_STREAM("SVHController",
631  "Received a get/set current setting packet for channel " << channel);
632  SVH_LOG_DEBUG_STREAM("SVHController",
633  "wmn " << m_current_settings[channel].wmn << " "
634  << "wmx " << m_current_settings[channel].wmx << " "
635  << "ky " << m_current_settings[channel].ky << " "
636  << "dt " << m_current_settings[channel].dt << " "
637  << "imn " << m_current_settings[channel].imn << " "
638  << "imx " << m_current_settings[channel].imx << " "
639  << "kp " << m_current_settings[channel].kp << " "
640  << "ki " << m_current_settings[channel].ki << " "
641  << "umn " << m_current_settings[channel].umn << " "
642  << "umx " << m_current_settings[channel].umx << " ");
643  }
644  else
645  {
646  SVH_LOG_ERROR_STREAM("SVHController",
647  "Received a get/set current setting packet for ILLEGAL channel "
648  << channel << "- packet ignored!");
649  }
650  break;
653  // std::cout << "Recieved: Controller State RAW Data: " << ab; // for really intensive
654  // debugging
655  ab >> m_controller_state;
656  // std::cout << "Received controllerState interpreded data: "<< m_controller_state <<
657  // std::endl; // for really intensive debugging
658  SVH_LOG_DEBUG_STREAM("SVHController", "Received a get/set controler state packet ");
659  SVH_LOG_DEBUG_STREAM("SVHController",
660  "Controllerstate (NO HEX):"
661  << "pwm_fault "
662  << "0x" << static_cast<int>(m_controller_state.pwm_fault) << " "
663  << "pwm_otw "
664  << "0x" << static_cast<int>(m_controller_state.pwm_otw) << " "
665  << "pwm_reset "
666  << "0x" << static_cast<int>(m_controller_state.pwm_reset) << " "
667  << "pwm_active "
668  << "0x" << static_cast<int>(m_controller_state.pwm_active) << " "
669  << "pos_ctr "
670  << "0x" << static_cast<int>(m_controller_state.pos_ctrl) << " "
671  << "cur_ctrl "
672  << "0x" << static_cast<int>(m_controller_state.cur_ctrl));
673  break;
676  SVH_LOG_DEBUG_STREAM("SVHController", "Received a get/set encoder settings packet ");
677  ab >> m_encoder_settings;
678  break;
680  // std::cout << "Recieved: Firmware Settings RAW Data: " << ab; // for really intensive
681  // debugging
682  ab >> m_firmware_info;
683  SVH_LOG_INFO_STREAM("SVHController",
684  "Hardware is using the following Firmware: "
685  << m_firmware_info.svh << " Version: " << m_firmware_info.version_major
686  << "." << m_firmware_info.version_minor << " : "
687  << m_firmware_info.text);
688  break;
689  default:
690  SVH_LOG_ERROR_STREAM("SVHController",
691  "Received a Packet with unknown address: " << (packet.address & 0x0F)
692  << " - ignoring packet");
693  break;
694  }
695 }
696 
698  SVHControllerFeedback& controller_feedback)
699 {
700  if (channel >= 0 && static_cast<uint8_t>(channel) < m_controller_feedback.size())
701  {
702  controller_feedback = m_controller_feedback[channel];
703  return true;
704  }
705  else
706  {
707  SVH_LOG_WARN_STREAM("SVHController",
708  "GetFeedback was requested for unknown channel: " << channel
709  << "- ignoring request");
710  return false;
711  }
712 }
713 
715  SVHControllerFeedbackAllChannels& controller_feedback)
716 {
717  controller_feedback.feedbacks = m_controller_feedback;
718 }
719 
721  SVHPositionSettings& position_settings)
722 {
723  if (channel >= 0 && static_cast<uint8_t>(channel) < m_position_settings.size())
724  {
725  position_settings = m_position_settings[channel];
726  return true;
727  }
728  else
729  {
731  "SVHController",
732  "GetPositionSettings was requested for unknown channel: " << channel << "- ignoring request");
733  return false;
734  }
735 }
736 
738  SVHCurrentSettings& current_settings)
739 {
740  if (channel >= 0 && static_cast<uint8_t>(channel) < m_current_settings.size())
741  {
742  current_settings = m_current_settings[channel];
743  return true;
744  }
745  else
746  {
748  "SVHController",
749  "GetCurrentSettings was requested for unknown channel: " << channel << "- ignoring request");
750  return false;
751  }
752 }
753 
755 {
756  return m_firmware_info;
757 }
758 
760 {
762  // The serial interface also keeps track about these counts
764  SVH_LOG_DEBUG_STREAM("SVHController", "Received package count resetted");
765 }
766 
768 {
769  if (m_serial_interface != NULL)
770  {
772  }
773  else
774  {
775  SVH_LOG_WARN_STREAM("SVHController",
776  "Request for transmit packet count could not be answered as the device is "
777  "not connected - ignoring request");
778  return 0;
779  }
780 }
781 
783 {
785 }
786 
788 {
789  return ((1 << channel & m_enable_mask) > 0);
790 }
791 
792 
793 } // namespace driver_svh
SVHFirmwareInfo getFirmwareInfo()
get the latest stored Firmware information from the controller (NOT THE HARDWARE) ...
void requestPositionSettings(const SVHChannel &channel)
request the settings of the position controller for a specific channel
const uint8_t SVH_GET_POSITION_SETTINGS
Requests the active settings of the position controller.
uint16_t pos_ctrl
Enable/Disable of position controller (0x0001 to Activate )
void disableChannel(const SVHChannel &channel)
Disable one or all motor channels.
SVHFirmwareInfo m_firmware_info
Latest firmware info.
Structure for transmitting all controllcommands at once.
std::vector< SVHCurrentSettings > m_current_settings
vector of current controller parameters for each finger
SVHEncoderSettings m_encoder_settings
Currently active encoder settings.
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
const uint8_t SVH_GET_CONTROL_FEEDBACK
Request the position and current of a channel to be sent.
unsigned int transmittedPacketCount()
get number of transmitted packets
unsigned int getSentPackageCount()
requests the number of sent packages. Request ist transferred to the serial interface that knows abou...
void receivedPacketCallback(const SVHSerialPacket &packet, unsigned int packet_count)
callback function for interpretation of packages
void getControllerFeedbackAllChannels(SVHControllerFeedbackAllChannels &controller_feedback)
Get all currently available controllerfeedbacks.
The SVHCurrentSettings save the current controller paramters for a single motor.
const uint8_t SVH_SET_CONTROL_COMMAND
Sets the target position of a channel.
#define SVH_LOG_INFO_STREAM(NAME, M)
Definition: Logger.h:46
static const float CHANNEL_EFFORT_CONSTANTS[9][2]
Effort multipliers to calculate the torque of the motors for the individual channels.
const uint8_t SVH_SET_ENCODER_VALUES
Set new encoder scalings.
uint16_t version_minor
Minor version number.
uint8_t address
Adress denotes the actual function of the package.
void close()
canceling receive thread and closing connection to serial port
bool getControllerFeedback(const SVHChannel &channel, SVHControllerFeedback &controller_feedback)
request the latest stored controllerfeedback (current, position) from the controller.
std::vector< uint8_t > array
array of template type TArray
bool connect(const std::string &dev_name)
Open serial device connection.
const uint8_t SVH_GET_CONTROLLER_STATE
Requests the state of the controller (active,faults,enabled channels)
unsigned int getReceivedPackageCount()
request the number of correctly received packages. This number is refreshed every time the serialinte...
std::vector< uint32_t > scalings
encoderSettings consist of multipliers for each encoder
void requestControllerState()
Request current controller state (mainly usefull for debug purposes)
std::vector< SVHControllerFeedback > feedbacks
Vector holding multiple channels.
bool sendPacket(SVHSerialPacket &packet)
function for sending packets via serial device to the SVH
unsigned int m_received_package_count
std::vector< uint8_t > data
Payload of the package.
void setControllerTarget(const SVHChannel &channel, const int32_t &position)
Set new position target for finger index.
bool connect(const std::string &dev_name)
connecting to serial device and starting receive thread
std::vector< SVHControllerFeedback > m_controller_feedback
ControllerFeedback indicates current position and current per finger.
const uint8_t SVH_SET_CONTROLLER_STATE
Sets new controller states (enable channels, clear faults)
bool isEnabled(const SVHChannel &channel)
Check if a channel was enabled.
#define SVH_LOG_DEBUG_STREAM(NAME, M)
Definition: Logger.h:39
const uint8_t SVH_GET_ENCODER_VALUES
Request the current encoder scalings.
#define SVH_LOG_ERROR_STREAM(NAME, M)
Definition: Logger.h:60
void requestControllerFeedback(const SVHChannel &channel)
request feedback (position and current) to a specific channel
void setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings &current_settings)
activate a new set of current controller settings for a specific channel
void receivedPacketCallback(const SVHSerialPacket &packet, unsigned int packet_count)
The SVHFirmwareInfo holds the data of a firmware response from the hardware.
The SVHControllerFeedback saves the feedback of a single motor.
const uint8_t SVH_SET_CURRENT_SETTINGS
Sets new settings for the current controller.
void disconnect()
disconnect serial device
ControlCommands are given as a single target position for the position controller (given in ticks) ...
void appendWithoutConversion(const T &data)
add data without any byte conversion
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
request the latest stored positionsettings from the controller
uint16_t version_major
Major version number.
uint16_t cur_ctrl
Enable/Disbale of current controller (0x0001 to Activate)
const uint8_t SVH_SET_POSITION_SETTINGS
Sets new settings for the position controller.
static const char * m_channel_description[]
Description values to get the corresponding string value to a channel enum.
std::vector< SVHPositionSettings > m_position_settings
vector of position controller parameters for each finger
const uint8_t SVH_GET_CURRENT_SETTINGS
Requests the active settings of the current controller.
SVHController()
Constructs a controller class for the SCHUNK five finger hand.
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings &current_settings)
request the latest stored currentsettings from the controller
This class controls the the SCHUNK five finger hand.
Definition: SVHController.h:87
void setControllerTargetAllChannels(const std::vector< int32_t > &positions)
Setting new position controller target for all fingers.
SVHControllerState m_controller_state
Currently active controllerstate on the HW Controller (indicates if PWM active etc.)
The SVHPositionSettings save the position controller paramters for a single motor.
SVHSerialInterface * m_serial_interface
Serial interface for transmission and reveibing of data packets.
void reset(size_t array_size=1)
Resets the Arraybuilder to initial state, all values will be deleted.
The SVHControllerState indicates the current state of the MeCoVis controller IC which is used in the ...
const uint8_t SVH_GET_CONTROL_FEEDBACK_ALL
Requests the positions and currents of ALL channels.
const uint8_t SVH_SET_CONTROL_COMMAND_ALL
Sends the target position to ALL the channels.
uint16_t m_enable_mask
Bitmask to tell which fingers are enabled.
The SVHControllerFeedbackAllChannes saves the feedback of a all motors.
const uint8_t SVH_GET_FIRMWARE_INFO
Request the firmware info to be transmitted.
Basic communication handler for the SCHUNK five finger hand.
void resetTransmitPackageCount()
resetTransmitPackageCount Resets the transmitpackage count to zero
void requestEncoderValues()
read out the mutipliers for the encoders from the hardware
void requestCurrentSettings(const SVHChannel &channel)
request the settings of the current controller for a specific channel
bool isConnected()
returns connected state of serial device
#define SVH_LOG_WARN_STREAM(NAME, M)
Definition: Logger.h:53
The SVHEncoderSettings hold the settings for the encoder scaling of each channel. ...
void setEncoderValues(const SVHEncoderSettings &encoder_settings)
sends a new set of encodervalues to the hardware
The SerialPacket holds the (non generated) header and data of one message to the SVH-Hardware.
void requestFirmwareInfo()
request a transmission of formware information
void enableChannel(const SVHChannel &channel)
Enable one or all motor channels.


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