#include <SVHFingerManager.h>
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 ¤t) |
returns current value of channel | |
bool | getCurrentSettings (const SVHChannel &channel, SVHCurrentSettings ¤t_settings) |
returns actual current controller settings of channel | |
std::vector< SVHCurrentSettings > | getDefaultCurrentSettings () |
get default current settings. These are either values previously set from calling software or hardcoded defaults | |
std::vector< SVHPositionSettings > | getDefaultPositionSettings (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 ¤t_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 ¤t_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) | |
SVHController * | m_controller |
pointer to svh controller | |
std::vector< SVHCurrentSettings > | m_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) | |
SVHFeedbackPollingThread * | m_feedback_thread |
pointer to svh controller | |
std::vector< SVHHomeSettings > | m_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_t > | m_position_home |
home position after complete reset of each channel | |
std::vector< int32_t > | m_position_max |
max position vector for each channel | |
std::vector< int32_t > | m_position_min |
min position vector for each channel | |
std::vector< SVHPositionSettings > | m_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< 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. | |
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) |
This class manages controller parameters and the finger reset.
Definition at line 63 of file SVHFingerManager.h.
The Hints enum provides mapping to hints that can be sent to the web-diagnostic interface.
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.
eST_DEACTIVATED | |
eST_RESETTING | |
eST_RESETTED | |
eST_ENABLED | |
eST_PARTIALLY_ENABLED | |
eST_FAULT | |
eST_DIMENSION |
Definition at line 70 of file SVHFingerManager.h.
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.
autostart | if set to true, the driver will immediately connect to the hardware and try to reset all fingers |
dev_name | the dev to use for autostart. Default is /dev/ttyUSB0 |
Definition at line 42 of file SVHFingerManager.cpp.
driver_svh::SVHFingerManager::~SVHFingerManager | ( | ) | [virtual] |
Definition at line 113 of file SVHFingerManager.cpp.
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.
dev_name | file handle of the serial device e.g. "/dev/ttyUSB0" |
_retry_count | The number of times a connection is tried to be established if at least one package was received |
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.
channel | Channel to Convert for (each one has different offset) |
position | The desired position given in RAD |
Definition at line 1308 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.
channel | Channel to Convert for (each one has different offset) |
ticks | The current position in ticks |
Definition at line 1325 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
channel | the channel the settings are meant for |
current_settings | the settings to evaluate |
Definition at line 1033 of file SVHFingerManager.cpp.
void driver_svh::SVHFingerManager::disableChannel | ( | const SVHChannel & | channel | ) |
disable controller of channel
channel | channel to disable |
Definition at line 627 of file SVHFingerManager.cpp.
disconnect SCHUNK five finger hand
Definition at line 288 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::enableChannel | ( | const SVHChannel & | channel | ) |
enable controller of channel
channel | channel to enable |
Definition at line 580 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::getCurrent | ( | const SVHChannel & | channel, |
double & | current | ||
) |
returns current value of channel
channel | channel to get the current of |
current | current of the given channel in [mA] |
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
channel | channel to get the current controller settings for |
current_settings | settings currently active for the current controller |
Definition at line 1007 of file SVHFingerManager.cpp.
std::vector< SVHCurrentSettings > driver_svh::SVHFingerManager::getDefaultCurrentSettings | ( | ) |
get default current settings. These are either values previously set from calling software or hardcoded defaults
Definition at line 1192 of file SVHFingerManager.cpp.
std::vector< SVHPositionSettings > driver_svh::SVHFingerManager::getDefaultPositionSettings | ( | 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)
returns parameters for position settings either the default ones or parameters that have been set from outside
Definition at line 1229 of file SVHFingerManager.cpp.
getFirmwareInfo Requests the firmware information from the harware, waits a bit and returns the last one read
Definition at line 1367 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)
channel | channel to get the position of |
position | position the given channel ist at |
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
channel | channel to get the position settings for |
position_settings | settings currently active for the position controller |
Definition at line 1020 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::isConnected | ( | ) | [inline] |
returns connected state of finger manager
Definition at line 121 of file SVHFingerManager.h.
bool driver_svh::SVHFingerManager::isEnabled | ( | const SVHChannel & | channel | ) |
returns true, if current channel has been enabled
channel | channel to check if it is enabled |
Definition at line 931 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::isHomed | ( | const SVHChannel & | channel | ) |
returns true, if current channel has been resetted
channel |
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.
channel | |
target_position |
Definition at line 1342 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::requestControllerFeedback | ( | const SVHChannel & | channel | ) |
send request controller feedback paket
channel | channel to request the feedback for |
Definition at line 666 of file SVHFingerManager.cpp.
sends request controller feedback packet for all channels
requests the current controller state to be updated
Definition at line 1357 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::resetChannel | ( | const SVHChannel & | channel | ) |
reset function for channel
reset function for a single finger
channel | Channel to reset |
Definition at line 325 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::setAllTargetPositions | ( | const std::vector< double > & | positions | ) |
set all target positions at once
positions | Vector 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 |
Definition at line 806 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::setCurrentSettings | ( | const SVHChannel & | channel, |
const SVHCurrentSettings & | current_settings | ||
) |
overwrite current parameters
channel | channel to set the current settings for |
current_settings | settings of the current controller for a specific channel |
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
channel | channel to set the home settings for |
home_settings | settings indicating the movement range of a finger, its reset direction and idle position |
Definition at line 1140 of file SVHFingerManager.cpp.
void driver_svh::SVHFingerManager::setMovementState | ( | const MovementState & | state | ) |
setMovementState Updates the movement state of the overll hand indicating the overall status
state | current movement state |
Definition at line 995 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::setPositionSettings | ( | const SVHChannel & | channel, |
const SVHPositionSettings & | position_settings | ||
) |
overwrite position parameters
channel | channel to set the positoon settings for |
position_settings | settings of the position controller to be used |
Definition at line 1115 of file SVHFingerManager.cpp.
void driver_svh::SVHFingerManager::setResetSpeed | ( | const float & | speed | ) |
setResetSpeed Set the speed percentage during reset
speed | percent of the normal speed used during reset Allowed values 0.0-1.0 |
Definition at line 1295 of file SVHFingerManager.cpp.
void driver_svh::SVHFingerManager::setResetTimeout | ( | const int & | resetTimeout | ) |
setResetTimeout Helper function to set the timout durind rest of fingers
resetTimeout | timeout in Seconds. Values smaler than 0 will be interpreted as 0 |
Definition at line 1362 of file SVHFingerManager.cpp.
bool driver_svh::SVHFingerManager::setTargetPosition | ( | const SVHChannel & | channel, |
double | position, | ||
double | current | ||
) |
set target position of a channel
channel | channel to set the target position for |
position | target position in [rad] |
current | max current to use for that position |
Definition at line 868 of file SVHFingerManager.cpp.
Definition at line 419 of file SVHFingerManager.h.
bool driver_svh::SVHFingerManager::m_connected [private] |
holds the connected state
Definition at line 322 of file SVHFingerManager.h.
bool driver_svh::SVHFingerManager::m_connection_feedback_given [private] |
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.
std::vector<SVHCurrentSettings> driver_svh::SVHFingerManager::m_current_settings [private] |
Vector of current controller parameters for each finger (as given by external config)
Definition at line 358 of file SVHFingerManager.h.
std::vector<bool> driver_svh::SVHFingerManager::m_current_settings_given [private] |
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.
std::vector<SVHHomeSettings> driver_svh::SVHFingerManager::m_home_settings [private] |
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.
std::vector<bool> driver_svh::SVHFingerManager::m_is_homed [private] |
vector storing reset flags for each channel
Definition at line 343 of file SVHFingerManager.h.
std::vector<bool> driver_svh::SVHFingerManager::m_is_switched_off [private] |
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.
std::vector<int32_t> driver_svh::SVHFingerManager::m_position_home [private] |
home position after complete reset of each channel
Definition at line 340 of file SVHFingerManager.h.
std::vector<int32_t> driver_svh::SVHFingerManager::m_position_max [private] |
max position vector for each channel
Definition at line 337 of file SVHFingerManager.h.
std::vector<int32_t> driver_svh::SVHFingerManager::m_position_min [private] |
min position vector for each channel
Definition at line 334 of file SVHFingerManager.h.
std::vector<SVHPositionSettings> driver_svh::SVHFingerManager::m_position_settings [private] |
Vector of position controller parameters for each finger (as given by external config)
Definition at line 363 of file SVHFingerManager.h.
std::vector<bool> driver_svh::SVHFingerManager::m_position_settings_given [private] |
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.
std::vector<double> driver_svh::SVHFingerManager::m_reset_current_factor [private] |
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.
std::vector<SVHChannel> driver_svh::SVHFingerManager::m_reset_order [private] |
vector storing the reset order of the channels
Definition at line 376 of file SVHFingerManager.h.
float driver_svh::SVHFingerManager::m_reset_speed_factor [private] |
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.
std::string driver_svh::SVHFingerManager::m_serial_device [private] |
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.
std::vector<double> driver_svh::SVHFingerManager::m_ticks2rad [private] |
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.