Public Types | Public Member Functions | Private Member Functions | Private Attributes
driver_svh::SVHFingerManager Class Reference

#include <SVHFingerManager.h>

List of all members.

Public Types

enum  Hints {
  eHT_DEVICE_NOT_FOUND, eHT_CONNECTION_FAILED, eHT_NOT_RESETTED, eHT_NOT_CONNECTED,
  eHT_RESET_FAILED, eHT_CHANNEL_SWITCHED_OF, eHT_DANGEROUS_CURRENTS, eHT_DIMENSION
}
 The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface. More...
enum  MovementState {
  eST_DEACTIVATED, eST_RESETTING, eST_RESETTED, eST_ENABLED,
  eST_PARTIALLY_ENABLED, eST_FAULT, eST_DIMENSION
}
 The MovementState enum indicated the overall state of the hand. Currently only used for updating the status websocket. More...

Public Member Functions

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.
void disableChannel (const SVHChannel &channel)
 disable controller of channel
void disconnect ()
 disconnect SCHUNK five finger hand
bool enableChannel (const SVHChannel &channel)
 enable controller of channel
bool getCurrent (const SVHChannel &channel, double &current)
 returns current value of channel
bool getCurrentSettings (const SVHChannel &channel, SVHCurrentSettings &current_settings)
 returns actual current controller settings of channel
std::vector< SVHCurrentSettingsgetDefaultCurrentSettings ()
 get default current settings. These are either values previously set from calling software or hardcoded defaults
std::vector< SVHPositionSettingsgetDefaultPositionSettings (const bool &reset=false)
 get default position settings. These are either values previously set from calling software or hardcoded defaults reset true if the Positions settins are to be used during reset (reduced speed)
SVHFirmwareInfo getFirmwareInfo ()
 getFirmwareInfo Requests the firmware information from the harware, waits a bit and returns the last one read
bool getPosition (const SVHChannel &channel, double &position)
 returns position value of channel (will not acces hardware but return latest value)
bool getPositionSettings (const SVHChannel &channel, SVHPositionSettings &position_settings)
 returns actual position controller settings of channel
bool isConnected ()
 returns connected state of finger manager
bool isEnabled (const SVHChannel &channel)
 returns true, if current channel has been enabled
bool isHomed (const SVHChannel &channel)
 returns true, if current channel has been resetted
bool requestControllerFeedback (const SVHChannel &channel)
 send request controller feedback paket
bool requestControllerFeedbackAllChannels ()
 sends request controller feedback packet for all channels
void requestControllerState ()
bool resetChannel (const SVHChannel &channel)
 reset function for channel
bool setAllTargetPositions (const std::vector< double > &positions)
 set all target positions at once
bool setCurrentSettings (const SVHChannel &channel, const SVHCurrentSettings &current_settings)
 overwrite current parameters
void setDefaultHomeSettings ()
 initialize the homing settings with hardcoded defaults. These can be overwritten by the setHomeSettings function
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 for the fingers
void setMovementState (const MovementState &state)
 setMovementState Updates the movement state of the overll hand indicating the overall status
bool setPositionSettings (const SVHChannel &channel, const SVHPositionSettings &position_settings)
 overwrite position parameters
void setResetSpeed (const float &speed)
 setResetSpeed Set the speed percentage during reset
void setResetTimeout (const int &resetTimeout)
 setResetTimeout Helper function to set the timout durind rest of fingers
bool setTargetPosition (const SVHChannel &channel, double position, double current)
 set target position of a channel
 SVHFingerManager (const std::vector< bool > &disable_mask=std::vector< bool >(9, false), const uint32_t &reset_timeout=5)
virtual ~SVHFingerManager ()

Private Member Functions

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 channels.
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 channels.
bool currentSettingsAreSafe (const SVHChannel &channel, const SVHCurrentSettings &current_settings)
 currentSettingsAreSafe helper function to check for the most important values of the current settings
bool isInsideBounds (const SVHChannel &channel, const int32_t &target_position)
 Check bounds of target positions.

Private Attributes

SVHControllerFeedback debug_feedback
bool m_connected
 holds the connected state
bool m_connection_feedback_given
 Helper variable to check if feedback was printed (will be replaced by a better solution in the future)
SVHControllerm_controller
 pointer to svh controller
std::vector< SVHCurrentSettingsm_current_settings
 Vector of current controller parameters for each finger (as given by external config)
std::vector< bool > m_current_settings_given
 Information about the validity of externaly given values for the current settings (easier to use this way)
SVHFeedbackPollingThreadm_feedback_thread
 pointer to svh controller
std::vector< SVHHomeSettingsm_home_settings
 Vector of home settings for each finger (as given by external config)
int8_t m_homing_timeout
 vector storing reset flags for each finger
std::vector< bool > m_is_homed
 vector storing reset flags for each channel
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 but not executed on hardware
MovementState m_movement_state
 Overall movement State to indicate what the hand is doing at the moment.
std::vector< int32_tm_position_home
 home position after complete reset of each channel
std::vector< int32_tm_position_max
 max position vector for each channel
std::vector< int32_tm_position_min
 min position vector for each channel
std::vector< SVHPositionSettingsm_position_settings
 Vector of position controller parameters for each finger (as given by external config)
std::vector< bool > m_position_settings_given
 Information about the validity of externaly given values for the position settings (easier to use this way)
std::vector< double > m_reset_current_factor
 Vector containing factors for the currents at reset. Vector containing factors for the currents at reset. A hard stop is found if the maxCurrent (first 2 CurrentSettingsValues) x the reset factor was reached. 0.75 by default Beware. Setting this value very high might result in damage to the motors during reset.
std::vector< SVHChannelm_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.
uint32_t m_reset_timeout
 Time in seconds after which the a reset is aborted if no change in current is observable.
std::string m_serial_device
 m_serial_device Device handle of the device to use, is overwritten if connect is called with an argument
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)

Detailed Description

This class manages controller parameters and the finger reset.

Definition at line 63 of file SVHFingerManager.h.


Member Enumeration Documentation

The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface.

Enumerator:
eHT_DEVICE_NOT_FOUND 
eHT_CONNECTION_FAILED 
eHT_NOT_RESETTED 
eHT_NOT_CONNECTED 
eHT_RESET_FAILED 
eHT_CHANNEL_SWITCHED_OF 
eHT_DANGEROUS_CURRENTS 
eHT_DIMENSION 

Definition at line 84 of file SVHFingerManager.h.

The MovementState enum indicated the overall state of the hand. Currently only used for updating the status websocket.

Enumerator:
eST_DEACTIVATED 
eST_RESETTING 
eST_RESETTED 
eST_ENABLED 
eST_PARTIALLY_ENABLED 
eST_FAULT 
eST_DIMENSION 

Definition at line 70 of file SVHFingerManager.h.


Constructor & Destructor Documentation

driver_svh::SVHFingerManager::SVHFingerManager ( const std::vector< bool > &  disable_mask = std::vector<bool>(9,false),
const uint32_t reset_timeout = 5 
)

Constructs a finger manager for the SCHUNK five finger hand.

Parameters:
autostartif set to true, the driver will immediately connect to the hardware and try to reset all fingers
dev_namethe dev to use for autostart. Default is /dev/ttyUSB0

Definition at line 42 of file SVHFingerManager.cpp.

Definition at line 113 of file SVHFingerManager.cpp.


Member Function Documentation

bool driver_svh::SVHFingerManager::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.

Parameters:
dev_namefile handle of the serial device e.g. "/dev/ttyUSB0"
_retry_countThe number of times a connection is tried to be established if at least one package was received
Returns:
true if connection was succesful

Definition at line 127 of file SVHFingerManager.cpp.

int32_t driver_svh::SVHFingerManager::convertRad2Ticks ( const SVHChannel channel,
const double &  position 
) [private]

Converts joint positions of a specific channel from RAD to ticks factoring in the offset of the channels.

Parameters:
channelChannel to Convert for (each one has different offset)
positionThe desired position given in RAD
Returns:
The tick value corresponing to the RAD input

Definition at line 1320 of file SVHFingerManager.cpp.

double driver_svh::SVHFingerManager::convertTicks2Rad ( const SVHChannel channel,
const int32_t ticks 
) [private]

Converts joint positions of a specific channel from ticks to RAD factoring in the offset of the channels.

Parameters:
channelChannel to Convert for (each one has different offset)
ticksThe current position in ticks
Returns:
the RAD Value corresponding to the tick value of a given channel

Definition at line 1337 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::currentSettingsAreSafe ( const SVHChannel channel,
const SVHCurrentSettings current_settings 
) [private]

currentSettingsAreSafe helper function to check for the most important values of the current settings

Parameters:
channelthe channel the settings are meant for
current_settingsthe settings to evaluate
Returns:
true if they are "reasonable safe". Only the most vile settings will be rejected!

Definition at line 1033 of file SVHFingerManager.cpp.

disable controller of channel

Parameters:
channelchannel to disable

Definition at line 627 of file SVHFingerManager.cpp.

disconnect SCHUNK five finger hand

Definition at line 288 of file SVHFingerManager.cpp.

enable controller of channel

Parameters:
channelchannel to enable
Returns:
true if the enabling was successful

Definition at line 580 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::getCurrent ( const SVHChannel channel,
double &  current 
)

returns current value of channel

Parameters:
channelchannel to get the current of
currentcurrent of the given channel in [mA]
Returns:
bool true if a valid result was requested (i.e. an existing channel)

Definition at line 790 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::getCurrentSettings ( const SVHChannel channel,
SVHCurrentSettings current_settings 
)

returns actual current controller settings of channel

Parameters:
channelchannel to get the current controller settings for
current_settingssettings currently active for the current controller
Returns:
true if a valid result was requested (i.e. an existing channel)

Definition at line 1007 of file SVHFingerManager.cpp.

get default current settings. These are either values previously set from calling software or hardcoded defaults

Definition at line 1195 of file SVHFingerManager.cpp.

get default position settings. These are either values previously set from calling software or hardcoded defaults reset true if the Positions settins are to be used during reset (reduced speed)

returns parameters for position settings either the default ones or parameters that have been set from outside

Definition at line 1240 of file SVHFingerManager.cpp.

getFirmwareInfo Requests the firmware information from the harware, waits a bit and returns the last one read

Returns:
the last firmware information read (this may not be the one currently requested)

Definition at line 1379 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::getPosition ( const SVHChannel channel,
double &  position 
)

returns position value of channel (will not acces hardware but return latest value)

Parameters:
channelchannel to get the position of
positionposition the given channel ist at
Returns:
bool true if a valid result was requested (i.e. an existing channel)

Definition at line 679 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::getPositionSettings ( const SVHChannel channel,
SVHPositionSettings position_settings 
)

returns actual position controller settings of channel

Parameters:
channelchannel to get the position settings for
position_settingssettings currently active for the position controller
Returns:
true if a valid result was requested (i.e. an existing channel)

Definition at line 1020 of file SVHFingerManager.cpp.

returns connected state of finger manager

Returns:
bool true if the finger manager is connected to the hardware

Definition at line 121 of file SVHFingerManager.h.

returns true, if current channel has been enabled

Parameters:
channelchannel to check if it is enabled
Returns:
true if the channel is enabled, false otherwise

Definition at line 931 of file SVHFingerManager.cpp.

returns true, if current channel has been resetted

Parameters:
channel
Returns:

Definition at line 967 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::isInsideBounds ( const SVHChannel channel,
const int32_t target_position 
) [private]

Check bounds of target positions.

Parameters:
channel
target_position
Returns:

Definition at line 1354 of file SVHFingerManager.cpp.

send request controller feedback paket

Parameters:
channelchannel to request the feedback for
Returns:
true if the request was successfully send to the hardware

Definition at line 666 of file SVHFingerManager.cpp.

sends request controller feedback packet for all channels

Returns:
true if the request was successfully send to the hardware

requests the current controller state to be updated

Note:
This is a debuging function. Should not be called by users

Definition at line 1369 of file SVHFingerManager.cpp.

reset function for channel

reset function for a single finger

Parameters:
channelChannel to reset
Returns:
true if the reset was successful

Definition at line 325 of file SVHFingerManager.cpp.

set all target positions at once

Parameters:
positionsVector of positions to set as targets given in [rad]. Only the first eSVH_CHANNEL_DIMENSION (9) values will be considered. If less values are given all others are set to zero
Returns:
true if a valid and wellformed Target position for all fingers was given and send to the HW (i.e. inside the bound limits etc.)

Definition at line 806 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::setCurrentSettings ( const SVHChannel channel,
const SVHCurrentSettings current_settings 
)

overwrite current parameters

Parameters:
channelchannel to set the current settings for
current_settingssettings of the current controller for a specific channel
Returns:
true if a valid channel was selected

Definition at line 1078 of file SVHFingerManager.cpp.

initialize the homing settings with hardcoded defaults. These can be overwritten by the setHomeSettings function

Definition at line 1165 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::setHomeSettings ( const SVHChannel channel,
const SVHHomeSettings home_settings 
)

setHomeSettings set the home Settings which are maily used doring reset and provide the soft limit for the fingers

Parameters:
channelchannel to set the home settings for
home_settingssettings indicating the movement range of a finger, its reset direction and idle position
Returns:
true if a valid channel was selected

Definition at line 1140 of file SVHFingerManager.cpp.

setMovementState Updates the movement state of the overll hand indicating the overall status

Parameters:
statecurrent movement state
Note:
this is only used for monitoring purposes at the moment, driverwise there is no need to call it but it is used by web frontends

Definition at line 995 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::setPositionSettings ( const SVHChannel channel,
const SVHPositionSettings position_settings 
)

overwrite position parameters

Parameters:
channelchannel to set the positoon settings for
position_settingssettings of the position controller to be used
Returns:
true if a valid channel was selected

Definition at line 1115 of file SVHFingerManager.cpp.

void driver_svh::SVHFingerManager::setResetSpeed ( const float &  speed)

setResetSpeed Set the speed percentage during reset

Parameters:
speedpercent of the normal speed used during reset Allowed values 0.0-1.0

Definition at line 1307 of file SVHFingerManager.cpp.

void driver_svh::SVHFingerManager::setResetTimeout ( const int &  resetTimeout)

setResetTimeout Helper function to set the timout durind rest of fingers

Parameters:
resetTimeouttimeout in Seconds. Values smaler than 0 will be interpreted as 0

Definition at line 1374 of file SVHFingerManager.cpp.

bool driver_svh::SVHFingerManager::setTargetPosition ( const SVHChannel channel,
double  position,
double  current 
)

set target position of a channel

Parameters:
channelchannel to set the target position for
positiontarget position in [rad]
currentmax current to use for that position
Note:
CURRENTLY NOT SUPPORTED!! WILL BE IGNORED
Returns:
true if a valid target position was given and it could be sent to the hardware

Definition at line 868 of file SVHFingerManager.cpp.


Member Data Documentation

Definition at line 419 of file SVHFingerManager.h.

holds the connected state

Definition at line 322 of file SVHFingerManager.h.

Helper variable to check if feedback was printed (will be replaced by a better solution in the future)

Definition at line 325 of file SVHFingerManager.h.

pointer to svh controller

Definition at line 316 of file SVHFingerManager.h.

Vector of current controller parameters for each finger (as given by external config)

Definition at line 358 of file SVHFingerManager.h.

Information about the validity of externaly given values for the current settings (easier to use this way)

Definition at line 360 of file SVHFingerManager.h.

pointer to svh controller

Definition at line 319 of file SVHFingerManager.h.

Vector of home settings for each finger (as given by external config)

Definition at line 368 of file SVHFingerManager.h.

vector storing reset flags for each finger

Definition at line 328 of file SVHFingerManager.h.

vector storing reset flags for each channel

Definition at line 343 of file SVHFingerManager.h.

vector storing information if a finger is enabled. In Case it is all request for it will be granted but not executed on hardware

Definition at line 346 of file SVHFingerManager.h.

Overall movement State to indicate what the hand is doing at the moment.

Definition at line 349 of file SVHFingerManager.h.

home position after complete reset of each channel

Definition at line 340 of file SVHFingerManager.h.

max position vector for each channel

Definition at line 337 of file SVHFingerManager.h.

min position vector for each channel

Definition at line 334 of file SVHFingerManager.h.

Vector of position controller parameters for each finger (as given by external config)

Definition at line 363 of file SVHFingerManager.h.

Information about the validity of externaly given values for the position settings (easier to use this way)

Definition at line 365 of file SVHFingerManager.h.

Vector containing factors for the currents at reset. Vector containing factors for the currents at reset. A hard stop is found if the maxCurrent (first 2 CurrentSettingsValues) x the reset factor was reached. 0.75 by default Beware. Setting this value very high might result in damage to the motors during reset.

Definition at line 384 of file SVHFingerManager.h.

vector storing the reset order of the channels

Definition at line 376 of file SVHFingerManager.h.

Factor for determining the finger speed during reset. Only 0.0-1.0 is allowed.

Definition at line 352 of file SVHFingerManager.h.

Time in seconds after which the a reset is aborted if no change in current is observable.

Definition at line 355 of file SVHFingerManager.h.

m_serial_device Device handle of the device to use, is overwritten if connect is called with an argument

Definition at line 373 of file SVHFingerManager.h.

position conversion factor (ticks to RAD) for each channel

Definition at line 331 of file SVHFingerManager.h.

boost::shared_ptr<icl_comm::websocket::WsBroadcaster> driver_svh::SVHFingerManager::m_ws_broadcaster [private]

Websocket handle for updating diagnostic backend (OPTIONAL)

Definition at line 313 of file SVHFingerManager.h.


The documentation for this class was generated from the following files:


schunk_svh_driver
Author(s): Georg Heppner
autogenerated on Fri Apr 28 2017 02:31:09