This class controls the the SCHUNK five finger hand. More...
#include <SVHController.h>
Public Member Functions | |
bool | connect (const std::string &dev_name) |
Open serial device connection. | |
void | disableChannel (const SVHChannel &channel) |
Disable one or all motor channels. | |
void | disconnect () |
disconnect serial device | |
void | enableChannel (const SVHChannel &channel) |
Enable one or all motor channels. | |
bool | getControllerFeedback (const SVHChannel &channel, SVHControllerFeedback &controller_feedback) |
request the latest stored controllerfeedback (current, position) from the controller. | |
void | getControllerFeedbackAllChannels (SVHControllerFeedbackAllChannels &controller_feedback) |
Get all currently available controllerfeedbacks. | |
bool | getCurrentSettings (const SVHChannel &channel, SVHCurrentSettings ¤t_settings) |
request the latest stored currentsettings from the controller | |
SVHFirmwareInfo | getFirmwareInfo () |
get the latest stored Firmware information from the controller (NOT THE HARDWARE) | |
bool | getPositionSettings (const SVHChannel &channel, SVHPositionSettings &position_settings) |
request the latest stored positionsettings from the controller | |
unsigned int | getReceivedPackageCount () |
request the number of correctly received packages. This number is refreshed every time the serialinterace calls the receivedPacket callback | |
unsigned int | getSentPackageCount () |
requests the number of sent packages. Request ist transferred to the serial interface that knows about this count | |
bool | isEnabled (const SVHChannel &channel) |
Check if a channel was enabled. | |
void | receivedPacketCallback (const SVHSerialPacket &packet, unsigned int packet_count) |
callback function for interpretation of packages | |
void | requestControllerFeedback (const SVHChannel &channel) |
request feedback (position and current) to a specific channel | |
void | requestControllerState () |
Request current controller state (mainly usefull for debug purposes) | |
void | requestCurrentSettings (const SVHChannel &channel) |
request the settings of the current controller for a specific channel | |
void | requestEncoderValues () |
read out the mutipliers for the encoders from the hardware | |
void | requestFirmwareInfo () |
request a transmission of formware information | |
void | requestPositionSettings (const SVHChannel &channel) |
request the settings of the position controller for a specific channel | |
void | resetPackageCounts () |
resetPackageCounts sets the sent and reveived package counts to zero | |
void | setControllerTarget (const SVHChannel &channel, const int32_t &position) |
Set new position target for finger index. | |
void | setControllerTargetAllChannels (const std::vector< int32_t > &positions) |
Setting new position controller target for all fingers. | |
void | setCurrentSettings (const SVHChannel &channel, const SVHCurrentSettings ¤t_settings) |
activate a new set of current controller settings for a specific channel | |
void | setEncoderValues (const SVHEncoderSettings &encoder_settings) |
sends a new set of encodervalues to the hardware | |
void | setPositionSettings (const SVHChannel &channel, const SVHPositionSettings &position_settings) |
activate a new set of position controller settings for a specific channel | |
SVHController () | |
Constructs a controller class for the SCHUNK five finger hand. | |
~SVHController () | |
Static Public Attributes | |
static const float | channel_effort_constants [9] |
Effort multipliers to calculate the torque of the motors for the individual channels. | |
static const char * | m_channel_description [] |
Description values to get the corresponding string value to a channel enum. | |
Private Attributes | |
std::vector < SVHControllerFeedback > | m_controller_feedback |
ControllerFeedback indicates current position and current per finger. | |
SVHControllerState | m_controller_state |
Currently active controllerstate on the HW Controller (indicates if PWM active etc.) | |
std::vector< SVHCurrentSettings > | m_current_settings |
vector of current controller parameters for each finger | |
uint16_t | m_enable_mask |
Bitmask to tell which fingers are enabled. | |
SVHEncoderSettings | m_encoder_settings |
Currently active encoder settings. | |
SVHFirmwareInfo | m_firmware_info |
Latest firmware info. | |
std::vector< SVHPositionSettings > | m_position_settings |
vector of position controller parameters for each finger | |
unsigned int | m_received_package_count |
store how many packages where actually received. Updated every time the receivepacket callback is called | |
SVHSerialInterface * | m_serial_interface |
Serial interface for transmission and reveibing of data packets. |
This class controls the the SCHUNK five finger hand.
The controller manages all calls to the hardware and receives every feedback. All data is interpreted and stored in the apropriate objects that can be queried by others.
Definition at line 77 of file SVHController.h.
Constructs a controller class for the SCHUNK five finger hand.
Definition at line 77 of file SVHController.cpp.
SCHUNK five finger hand destructor Destructor, disable the serial device and shut down hand as far as possible
Definition at line 88 of file SVHController.cpp.
bool driver_svh::SVHController::connect | ( | const std::string & | dev_name | ) |
Open serial device connection.
dev_name | System handle (filename in linux) to the device |
Definition at line 100 of file SVHController.cpp.
void driver_svh::SVHController::disableChannel | ( | const SVHChannel & | channel | ) |
Disable one or all motor channels.
channel | Motor to deactivate |
Definition at line 262 of file SVHController.cpp.
disconnect serial device
Definition at line 116 of file SVHController.cpp.
void driver_svh::SVHController::enableChannel | ( | const SVHChannel & | channel | ) |
Enable one or all motor channels.
channel | Motor to activate |
Definition at line 174 of file SVHController.cpp.
bool driver_svh::SVHController::getControllerFeedback | ( | const SVHChannel & | channel, |
SVHControllerFeedback & | controller_feedback | ||
) |
request the latest stored controllerfeedback (current, position) from the controller.
channel | Motor to get the latest feedback to |
ControllerFeedback | (current, encoder position) of the specified channel |
Controllerfeedback (crurrent,channel) is stored/updated in the controller once it is send by the hardware. This is the case once a controlCommand has been send or the feedback has specifically been requested by using the getControllerFeedback() function
Definition at line 553 of file SVHController.cpp.
void driver_svh::SVHController::getControllerFeedbackAllChannels | ( | SVHControllerFeedbackAllChannels & | controller_feedback | ) |
Get all currently available controllerfeedbacks.
Definition at line 567 of file SVHController.cpp.
bool driver_svh::SVHController::getCurrentSettings | ( | const SVHChannel & | channel, |
SVHCurrentSettings & | current_settings | ||
) |
request the latest stored currentsettings from the controller
channel | Motor to get the currentsettings for |
position_settings | current settings to be returned |
Definition at line 586 of file SVHController.cpp.
get the latest stored Firmware information from the controller (NOT THE HARDWARE)
Definition at line 600 of file SVHController.cpp.
bool driver_svh::SVHController::getPositionSettings | ( | const SVHChannel & | channel, |
SVHPositionSettings & | position_settings | ||
) |
request the latest stored positionsettings from the controller
channel | Motor to get the positionsettings for |
position_settings | position settings to be returned |
Definition at line 572 of file SVHController.cpp.
unsigned int driver_svh::SVHController::getReceivedPackageCount | ( | ) |
request the number of correctly received packages. This number is refreshed every time the serialinterace calls the receivedPacket callback
Definition at line 626 of file SVHController.cpp.
unsigned int driver_svh::SVHController::getSentPackageCount | ( | ) |
requests the number of sent packages. Request ist transferred to the serial interface that knows about this count
Definition at line 613 of file SVHController.cpp.
bool driver_svh::SVHController::isEnabled | ( | const SVHChannel & | channel | ) |
Check if a channel was enabled.
channel | to check |
Definition at line 631 of file SVHController.cpp.
void driver_svh::SVHController::receivedPacketCallback | ( | const SVHSerialPacket & | packet, |
unsigned int | packet_count | ||
) |
callback function for interpretation of packages
packet | SerialPacket containing the raw data, integrity should have been checked by SerialInterface |
packet_count | count of received packets |
Definition at line 460 of file SVHController.cpp.
void driver_svh::SVHController::requestControllerFeedback | ( | const SVHChannel & | channel | ) |
request feedback (position and current) to a specific channel
channel | Motorchannel the feedback should be provided for |
Definition at line 326 of file SVHController.cpp.
Request current controller state (mainly usefull for debug purposes)
Definition at line 319 of file SVHController.cpp.
void driver_svh::SVHController::requestCurrentSettings | ( | const SVHChannel & | channel | ) |
request the settings of the current controller for a specific channel
channel | Motor to request the settings for |
Definition at line 384 of file SVHController.cpp.
read out the mutipliers for the encoders from the hardware
Definition at line 425 of file SVHController.cpp.
request a transmission of formware information
Definition at line 452 of file SVHController.cpp.
void driver_svh::SVHController::requestPositionSettings | ( | const SVHChannel & | channel | ) |
request the settings of the position controller for a specific channel
channel | Motor to request the settings for |
Definition at line 351 of file SVHController.cpp.
resetPackageCounts sets the sent and reveived package counts to zero
Definition at line 605 of file SVHController.cpp.
void driver_svh::SVHController::setControllerTarget | ( | const SVHChannel & | channel, |
const int32_t & | position | ||
) |
Set new position target for finger index.
channel | Motorchanel to set the target for |
position | Target position for the channel given in encoder Ticks |
Definition at line 128 of file SVHController.cpp.
void driver_svh::SVHController::setControllerTargetAllChannels | ( | const std::vector< int32_t > & | positions | ) |
Setting new position controller target for all fingers.
positions | Target positions for all fingers, Only the first nine values will be evaluated |
Definition at line 151 of file SVHController.cpp.
void driver_svh::SVHController::setCurrentSettings | ( | const SVHChannel & | channel, |
const SVHCurrentSettings & | current_settings | ||
) |
activate a new set of current controller settings for a specific channel
channel | Motor the new current controller settings will be applied to |
current_settings | new settings of the current controller |
Definition at line 399 of file SVHController.cpp.
void driver_svh::SVHController::setEncoderValues | ( | const SVHEncoderSettings & | encoder_settings | ) |
sends a new set of encodervalues to the hardware
encoder_settings | to set (prescalers) |
Definition at line 432 of file SVHController.cpp.
void driver_svh::SVHController::setPositionSettings | ( | const SVHChannel & | channel, |
const SVHPositionSettings & | position_settings | ||
) |
activate a new set of position controller settings for a specific channel
channel | Motor the new position controller settings will be applied to |
position_settings | new settings of the position controller |
Definition at line 358 of file SVHController.cpp.
const float driver_svh::SVHController::channel_effort_constants [static] |
{ 0.0000232, 0.0000232, 0.000009, 0.000016, 0.000009, 0.000016, 0.000009, 0.000009, 0.000016 }
Effort multipliers to calculate the torque of the motors for the individual channels.
Values are given in Nm/mA to be directly compatible to current output of the driver.
Definition at line 247 of file SVHController.h.
const char * driver_svh::SVHController::m_channel_description [static] |
{ "Thumb_Flexion", "Thumb_Opposition", "Index_Finger_Distal", "Index_Finger_Proximal", "Middle_Finger_Distal", "Middle_Finger_Proximal", "Ring_Finger", "Pinky", "Finger_Spread", NULL }
Description values to get the corresponding string value to a channel enum.
Description of the channels for enum matching:
Definition at line 244 of file SVHController.h.
std::vector<SVHControllerFeedback> driver_svh::SVHController::m_controller_feedback [private] |
ControllerFeedback indicates current position and current per finger.
Definition at line 262 of file SVHController.h.
Currently active controllerstate on the HW Controller (indicates if PWM active etc.)
Definition at line 265 of file SVHController.h.
std::vector<SVHCurrentSettings> driver_svh::SVHController::m_current_settings [private] |
vector of current controller parameters for each finger
Definition at line 256 of file SVHController.h.
Bitmask to tell which fingers are enabled.
Definition at line 279 of file SVHController.h.
Currently active encoder settings.
Definition at line 268 of file SVHController.h.
Latest firmware info.
Definition at line 271 of file SVHController.h.
std::vector<SVHPositionSettings> driver_svh::SVHController::m_position_settings [private] |
vector of position controller parameters for each finger
Definition at line 259 of file SVHController.h.
unsigned int driver_svh::SVHController::m_received_package_count [private] |
store how many packages where actually received. Updated every time the receivepacket callback is called
Definition at line 282 of file SVHController.h.
Serial interface for transmission and reveibing of data packets.
Definition at line 276 of file SVHController.h.