Program Listing for File SVHController.h

Return to documentation for file (/tmp/ws/src/schunk_svh_library/include/schunk_svh_library/control/SVHController.h)

//
// © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
// © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
//
// This file is part of the Schunk SVH Library.
//
// The Schunk SVH Library is free software: you can redistribute it and/or
// modify it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or (at your
// option) any later version.
//
// The Schunk SVH Library is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
// Public License for more details.
//
// You should have received a copy of the GNU General Public License along with
// the Schunk SVH Library. If not, see <https://www.gnu.org/licenses/>.
//


//----------------------------------------------------------------------
//----------------------------------------------------------------------
#ifndef DRIVER_SVH_SVH_CONTROLLER_H_INCLUDED
#define DRIVER_SVH_SVH_CONTROLLER_H_INCLUDED

#include <schunk_svh_library/ImportExport.h>
#include <schunk_svh_library/SVHFirmwareInfo.h>
#include <schunk_svh_library/control/SVHControlCommand.h>
#include <schunk_svh_library/control/SVHControllerFeedback.h>
#include <schunk_svh_library/control/SVHControllerState.h>
#include <schunk_svh_library/control/SVHCurrentSettings.h>
#include <schunk_svh_library/control/SVHEncoderSettings.h>
#include <schunk_svh_library/control/SVHPositionSettings.h>
#include <schunk_svh_library/serial/SVHReceiveThread.h>
#include <schunk_svh_library/serial/SVHSerialInterface.h>

namespace driver_svh {

enum
{
  SVH_ALL           = -1, // this should be used with care as not all functions support it yet
  SVH_THUMB_FLEXION = 0,
  SVH_THUMB_OPPOSITION, // wrist
  SVH_INDEX_FINGER_DISTAL,
  SVH_INDEX_FINGER_PROXIMAL,
  SVH_MIDDLE_FINGER_DISTAL,
  SVH_MIDDLE_FINGER_PROXIMAL,
  SVH_RING_FINGER,
  SVH_PINKY,
  SVH_FINGER_SPREAD,
  SVH_DIMENSION // 9
} typedef SVHChannel;

class DRIVER_SVH_IMPORT_EXPORT SVHController
{
public:
  SVHController();

  ~SVHController();

  bool connect(const std::string& dev_name);

  void disconnect();

  void setControllerTarget(const SVHChannel& channel, const int32_t& position);

  void setControllerTargetAllChannels(const std::vector<int32_t>& positions);


  // Access functions
  void enableChannel(const SVHChannel& channel);

  void disableChannel(const SVHChannel& channel);

  void requestControllerState();

  void requestControllerFeedback(const SVHChannel& channel);

  void requestPositionSettings(const SVHChannel& channel);

  void setPositionSettings(const SVHChannel& channel, const SVHPositionSettings& position_settings);

  void requestCurrentSettings(const SVHChannel& channel);

  void setCurrentSettings(const SVHChannel& channel, const SVHCurrentSettings& current_settings);

  void requestEncoderValues();

  void setEncoderValues(const SVHEncoderSettings& encoder_settings);


  void requestFirmwareInfo();

  void receivedPacketCallback(const SVHSerialPacket& packet, unsigned int packet_count);

  bool getControllerFeedback(const SVHChannel& channel, SVHControllerFeedback& controller_feedback);

  bool getPositionSettings(const SVHChannel& channel, SVHPositionSettings& position_settings);

  bool getCurrentSettings(const SVHChannel& channel, SVHCurrentSettings& current_settings);

  SVHFirmwareInfo getFirmwareInfo();

  unsigned int getSentPackageCount();

  unsigned int getReceivedPackageCount();

  void resetPackageCounts();

  bool isEnabled(const SVHChannel& channel);

  static const char* m_channel_description[];

  static const float CHANNEL_EFFORT_CONSTANTS[9][2];

  void getControllerFeedbackAllChannels(SVHControllerFeedbackAllChannels& controller_feedback);

private:
  // Data Structures for holding configurations and feedback of the Controller

  std::vector<SVHCurrentSettings> m_current_settings;

  std::vector<SVHPositionSettings> m_position_settings;

  std::vector<SVHControllerFeedback> m_controller_feedback;

  SVHControllerState m_controller_state;

  SVHEncoderSettings m_encoder_settings;

  SVHFirmwareInfo m_firmware_info;

  // Hardware control

  SVHSerialInterface* m_serial_interface;

  uint16_t m_enable_mask;

  unsigned int m_received_package_count;
};

} // namespace driver_svh

#endif