Go to the documentation of this file.
37 #ifndef DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
38 #define DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
89 SVHFingerManager(
const std::vector<bool>& disable_mask = std::vector<bool>(9,
false),
90 const uint32_t& reset_timeout = 5);
100 bool connect(
const std::string& dev_name =
"/dev/ttyUSB0",
const unsigned int& retry_count = 3);
125 bool enableChannel(
const SVHChannel& channel);
131 void disableChannel(
const SVHChannel& channel);
137 bool requestControllerFeedbackAllChannels();
144 bool requestControllerFeedback(
const SVHChannel& channel);
152 bool getPosition(
const SVHChannel& channel,
double& position);
160 bool getCurrent(
const SVHChannel& channel,
double& current);
170 bool setAllTargetPositions(
const std::vector<double>& positions);
179 bool setTargetPosition(
const SVHChannel& channel,
double position,
double current);
197 void requestControllerState();
229 bool getDiagnosticStatus(
const SVHChannel& channel,
struct DiagnosticState& diagnostic_status);
260 bool resetDiagnosticData(
const SVHChannel& channel);
268 std::vector<SVHCurrentSettings> getDefaultCurrentSettings();
273 std::vector<SVHPositionSettings> getDefaultPositionSettings(
const bool& reset =
false);
277 void setDefaultHomeSettings();
283 void setResetSpeed(
const float& speed);
289 void setResetTimeout(
const int& reset_timeout);
296 bool setMaxForce(
float max_force);
304 float setForceLimit(
const SVHChannel& channel,
float force_limit);
312 double convertmAtoN(
const SVHChannel& channel,
const int16_t& current);
322 SVHFirmwareInfo getFirmwareInfo(
const std::string& dev_name =
"/dev/ttyUSB0",
323 const unsigned int& retry_count = 3);
443 int32_t convertRad2Ticks(
const SVHChannel& channel,
const double& position);
451 double convertTicks2Rad(
const SVHChannel& channel,
const int32_t& ticks);
458 uint16_t convertNtomA(
const SVHChannel& channel,
const double& effort);
466 bool isInsideBounds(
const SVHChannel& channel,
const int32_t& target_position);
474 bool currentSettingsAreSafe(
const SVHChannel& channel,
std::string m_serial_device
m_serial_device Device handle of the device to use, is overwritten if connect is called with an argum...
std::vector< double > m_reset_current_factor
Vector containing factors for the currents at reset. Vector containing factors for the currents at re...
std::vector< bool > m_is_homed
vector storing reset flags for each channel
std::vector< bool > m_is_switched_off
std::vector< SVHChannel > m_reset_order
vector storing the reset order of the channels
std::vector< double > m_ticks2rad
position conversion factor (ticks to RAD) for each channel
std::chrono::seconds m_homing_timeout
Timeout for homing.
std::vector< double > m_diagnostic_position_maximum
vectors storing diagnostic information, position maximum
This class controls the the SCHUNK five finger hand.
double diagnostic_current_maximum
std::vector< double > m_diagnostic_current_maximum
vectors storing diagnostic information, current maximum
SVHControllerFeedback m_debug_feedback
double diagnostic_current_minimum
std::vector< double > m_diagnostic_deadlock
vectors storing diagnostic information, diagnostics deadlock
std::vector< SVHCurrentSettings > m_current_settings
Vector of current controller parameters for each finger (as given by external config)
SVHController * m_controller
pointer to svh controller
bool m_connected
holds the connected state
double diagnostic_deadlock
bool diagnostic_motor_state
std::vector< bool > m_position_settings_given
std::vector< SVHPositionSettings > m_position_settings
Vector of position controller parameters for each finger (as given by external config)
double diagnostic_position_maximum
bool isConnected()
returns connected state of finger manager
The SVHCurrentSettings save the current controller paramters for a single motor.
float m_reset_speed_factor
Factor for determining the finger speed during reset. Only 0.0-1.0 is allowed.
std::atomic< bool > m_poll_feedback
Flag whether to poll feedback periodically in the feedback thread.
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_diagnostic_current_state
vectors storing diagnostic information, current state
std::vector< bool > m_current_settings_given
std::vector< int32_t > m_position_max
max position vector for each channel
data sctructure for home positions
#define DRIVER_SVH_IMPORT_EXPORT
std::vector< double > m_diagnostic_current_minimum
vectors storing diagnostic information, current minimum
bool diagnostic_encoder_state
Hints
The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface.
std::vector< int32_t > m_position_home
home position after complete reset of each channel
float m_max_current_percentage
limit the maximum of the force / current of the finger as a percentage of the possible maximum
std::vector< double > m_diagnostic_position_minimum
vectors storing diagnostic information, position minimum
std::vector< SVHHomeSettings > m_home_settings
Vector of home settings for each finger (as given by external config)
double diagnostic_position_minimum
The SVHPositionSettings save the position controller paramters for a single motor.
std::chrono::seconds m_reset_timeout
Time in seconds after which the a reset is aborted if no change in current is observable.
std::vector< bool > m_diagnostic_encoder_state
vectors storing diagnostic information, encoder state
std::vector< int32_t > m_position_min
min position vector for each channel
SVHFirmwareInfo m_firmware_info
Firmware info of the connected Hand.
bool m_connection_feedback_given
std::thread m_feedback_thread
Thread for polling periodic feedback from the hardware.
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