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. More... | |
void | disableChannel (const SVHChannel &channel) |
Disable one or all motor channels. More... | |
void | disconnect () |
disconnect serial device More... | |
void | enableChannel (const SVHChannel &channel) |
Enable one or all motor channels. More... | |
bool | getControllerFeedback (const SVHChannel &channel, SVHControllerFeedback &controller_feedback) |
request the latest stored controllerfeedback (current, position) from the controller. More... | |
void | getControllerFeedbackAllChannels (SVHControllerFeedbackAllChannels &controller_feedback) |
Get all currently available controllerfeedbacks. More... | |
bool | getCurrentSettings (const SVHChannel &channel, SVHCurrentSettings ¤t_settings) |
request the latest stored currentsettings from the controller More... | |
SVHFirmwareInfo | getFirmwareInfo () |
get the latest stored Firmware information from the controller (NOT THE HARDWARE) More... | |
bool | getPositionSettings (const SVHChannel &channel, SVHPositionSettings &position_settings) |
request the latest stored positionsettings from the controller More... | |
unsigned int | getReceivedPackageCount () |
request the number of correctly received packages. This number is refreshed every time the serialinterace calls the receivedPacket callback More... | |
unsigned int | getSentPackageCount () |
requests the number of sent packages. Request ist transferred to the serial interface that knows about this count More... | |
bool | isEnabled (const SVHChannel &channel) |
Check if a channel was enabled. More... | |
void | receivedPacketCallback (const SVHSerialPacket &packet, unsigned int packet_count) |
callback function for interpretation of packages More... | |
void | requestControllerFeedback (const SVHChannel &channel) |
request feedback (position and current) to a specific channel More... | |
void | requestControllerState () |
Request current controller state (mainly usefull for debug purposes) More... | |
void | requestCurrentSettings (const SVHChannel &channel) |
request the settings of the current controller for a specific channel More... | |
void | requestEncoderValues () |
read out the mutipliers for the encoders from the hardware More... | |
void | requestFirmwareInfo () |
request a transmission of formware information More... | |
void | requestPositionSettings (const SVHChannel &channel) |
request the settings of the position controller for a specific channel More... | |
void | resetPackageCounts () |
resetPackageCounts sets the sent and reveived package counts to zero More... | |
void | setControllerTarget (const SVHChannel &channel, const int32_t &position) |
Set new position target for finger index. More... | |
void | setControllerTargetAllChannels (const std::vector< int32_t > &positions) |
Setting new position controller target for all fingers. More... | |
void | setCurrentSettings (const SVHChannel &channel, const SVHCurrentSettings ¤t_settings) |
activate a new set of current controller settings for a specific channel More... | |
void | setEncoderValues (const SVHEncoderSettings &encoder_settings) |
sends a new set of encodervalues to the hardware More... | |
void | setPositionSettings (const SVHChannel &channel, const SVHPositionSettings &position_settings) |
activate a new set of position controller settings for a specific channel More... | |
SVHController () | |
Constructs a controller class for the SCHUNK five finger hand. More... | |
~SVHController () | |
Static Public Attributes | |
static const float | CHANNEL_EFFORT_CONSTANTS [9][2] |
Effort multipliers to calculate the torque of the motors for the individual channels. More... | |
static const char * | m_channel_description [] |
Description values to get the corresponding string value to a channel enum. More... | |
Private Attributes | |
std::vector< SVHControllerFeedback > | m_controller_feedback |
ControllerFeedback indicates current position and current per finger. More... | |
SVHControllerState | m_controller_state |
Currently active controllerstate on the HW Controller (indicates if PWM active etc.) More... | |
std::vector< SVHCurrentSettings > | m_current_settings |
vector of current controller parameters for each finger More... | |
uint16_t | m_enable_mask |
Bitmask to tell which fingers are enabled. More... | |
SVHEncoderSettings | m_encoder_settings |
Currently active encoder settings. More... | |
SVHFirmwareInfo | m_firmware_info |
Latest firmware info. More... | |
std::vector< SVHPositionSettings > | m_position_settings |
vector of position controller parameters for each finger More... | |
unsigned int | m_received_package_count |
SVHSerialInterface * | m_serial_interface |
Serial interface for transmission and reveibing of data packets. More... | |
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 87 of file SVHController.h.
driver_svh::SVHController::SVHController | ( | ) |
Constructs a controller class for the SCHUNK five finger hand.
Definition at line 94 of file SVHController.cpp.
driver_svh::SVHController::~SVHController | ( | ) |
SCHUNK five finger hand destructor Destructor, disable the serial device and shut down hand as far as possible
Definition at line 109 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 121 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 313 of file SVHController.cpp.
void driver_svh::SVHController::disconnect | ( | ) |
disconnect serial device
Definition at line 138 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 218 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 697 of file SVHController.cpp.
void driver_svh::SVHController::getControllerFeedbackAllChannels | ( | SVHControllerFeedbackAllChannels & | controller_feedback | ) |
Get all currently available controllerfeedbacks.
Definition at line 714 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 737 of file SVHController.cpp.
SVHFirmwareInfo driver_svh::SVHController::getFirmwareInfo | ( | ) |
get the latest stored Firmware information from the controller (NOT THE HARDWARE)
Definition at line 754 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 720 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 782 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 767 of file SVHController.cpp.
bool driver_svh::SVHController::isEnabled | ( | const SVHChannel & | channel | ) |
Check if a channel was enabled.
channel | to check |
Definition at line 787 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 547 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 380 of file SVHController.cpp.
void driver_svh::SVHController::requestControllerState | ( | ) |
Request current controller state (mainly usefull for debug purposes)
Definition at line 373 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 455 of file SVHController.cpp.
void driver_svh::SVHController::requestEncoderValues | ( | ) |
read out the mutipliers for the encoders from the hardware
Definition at line 511 of file SVHController.cpp.
void driver_svh::SVHController::requestFirmwareInfo | ( | ) |
request a transmission of formware information
Definition at line 539 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 408 of file SVHController.cpp.
void driver_svh::SVHController::resetPackageCounts | ( | ) |
resetPackageCounts sets the sent and reveived package counts to zero
Definition at line 759 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 156 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 185 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 474 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 518 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 417 of file SVHController.cpp.
|
static |
Effort multipliers to calculate the torque of the motors for the individual channels.
Values are given in N/mA to be directly compatible to current output of the driver.
Definition at line 258 of file SVHController.h.
|
static |
Description values to get the corresponding string value to a channel enum.
Description of the channels for enum matching:
Definition at line 255 of file SVHController.h.
|
private |
ControllerFeedback indicates current position and current per finger.
Definition at line 273 of file SVHController.h.
|
private |
Currently active controllerstate on the HW Controller (indicates if PWM active etc.)
Definition at line 276 of file SVHController.h.
|
private |
vector of current controller parameters for each finger
Definition at line 267 of file SVHController.h.
|
private |
Bitmask to tell which fingers are enabled.
Definition at line 290 of file SVHController.h.
|
private |
Currently active encoder settings.
Definition at line 279 of file SVHController.h.
|
private |
Latest firmware info.
Definition at line 282 of file SVHController.h.
|
private |
vector of position controller parameters for each finger
Definition at line 270 of file SVHController.h.
|
private |
store how many packages where actually received. Updated every time the receivepacket callback is called
Definition at line 294 of file SVHController.h.
|
private |
Serial interface for transmission and reveibing of data packets.
Definition at line 287 of file SVHController.h.