30 #ifndef DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED    31 #define DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED    40 #include <boost/shared_ptr.hpp>    43 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_    44 #include <icl_comm_websocket/WsBroadcaster.h>    54 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_   100   SVHFingerManager(
const std::vector<bool> &disable_mask = std::vector<bool>(9,
false), 
const uint32_t &reset_timeout = 5);
   110   bool connect(
const std::string &dev_name = 
"/dev/ttyUSB0",
const unsigned int &_retry_count = 3);
   135   bool enableChannel(
const SVHChannel &channel);
   141   void disableChannel(
const SVHChannel &channel);
   147   bool requestControllerFeedbackAllChannels();
   154   bool requestControllerFeedback(
const SVHChannel &channel);
   162   bool getPosition(
const SVHChannel &channel, 
double &position);
   170   bool getCurrent(
const SVHChannel &channel, 
double ¤t);
   178   bool setAllTargetPositions(
const std::vector<double>& positions);
   187   bool setTargetPosition(
const SVHChannel &channel, 
double position, 
double current);
   213   void requestControllerState();
   261   std::vector<SVHCurrentSettings> getDefaultCurrentSettings();
   265   std::vector<SVHPositionSettings> getDefaultPositionSettings(
const bool& reset = 
false);
   268   void setDefaultHomeSettings();
   274   void setResetSpeed(
const float& speed);
   280   void setResetTimeout(
const int& resetTimeout);
   289   #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_   296   void updateWebSocket();
   302   void receivedHintMessage(
const int &hint);
   304   #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_ std::vector< SVHChannel > m_reset_order
vector storing the reset order of the channels 
 
float m_reset_speed_factor
Factor for determining the finger speed during reset. Only 0.0-1.0 is allowed. 
 
std::vector< bool > m_is_homed
vector storing reset flags for each channel 
 
std::vector< bool > m_position_settings_given
Information about the validity of externaly given values for the position settings (easier to use thi...
 
MovementState
The MovementState enum indicated the overall state of the hand. Currently only used for updating the ...
 
std::vector< SVHCurrentSettings > m_current_settings
Vector of current controller parameters for each finger (as given by external config) ...
 
SVHFeedbackPollingThread * m_feedback_thread
pointer to svh controller 
 
std::vector< int32_t > m_position_max
max position vector for each channel 
 
std::vector< double > m_ticks2rad
position conversion factor (ticks to RAD) for each channel 
 
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
Websocket handle for updating diagnostic backend (OPTIONAL) 
 
The SVHCurrentSettings save the current controller paramters for a single motor. 
 
#define DRIVER_SVH_IMPORT_EXPORT
 
int8_t m_homing_timeout
vector storing reset flags for each finger 
 
bool m_connection_feedback_given
Helper variable to check if feedback was printed (will be replaced by a better solution in the future...
 
bool isConnected()
returns connected state of finger manager 
 
std::string m_serial_device
m_serial_device Device handle of the device to use, is overwritten if connect is called with an argum...
 
MovementState m_movement_state
Overall movement State to indicate what the hand is doing at the moment. 
 
std::vector< int32_t > m_position_min
min position vector for each channel 
 
std::vector< SVHHomeSettings > m_home_settings
Vector of home settings for each finger (as given by external config) 
 
Hints
The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface. 
 
std::vector< SVHPositionSettings > m_position_settings
Vector of position controller parameters for each finger (as given by external config) ...
 
std::vector< int32_t > m_position_home
home position after complete reset of each channel 
 
The SVHFirmwareInfo holds the data of a firmware response from the hardware. 
 
The SVHControllerFeedback saves the feedback of a single motor. 
 
std::vector< bool > m_is_switched_off
vector storing information if a finger is enabled. In Case it is all request for it will be granted b...
 
uint32_t m_reset_timeout
Time in seconds after which the a reset is aborted if no change in current is observable. 
 
bool m_connected
holds the connected state 
 
std::vector< double > m_reset_current_factor
Vector containing factors for the currents at reset. Vector containing factors for the currents at re...
 
This class controls the the SCHUNK five finger hand. 
 
Thread for periodically requesting feedback messages from the SCHUNK five finger hand. 
 
The SVHPositionSettings save the position controller paramters for a single motor. 
 
SVHControllerFeedback debug_feedback
 
data sctructure for home positions 
 
std::vector< bool > m_current_settings_given
Information about the validity of externaly given values for the current settings (easier to use this...
 
SVHChannel
Channel indicates which motor to use in command calls. WARNING: DO NOT CHANGE THE ORDER OF THESE as i...
 
SVHController * m_controller
pointer to svh controller