62 "Index_Finger_Distal",
63 "Index_Finger_Proximal",
64 "Middle_Finger_Distal",
65 "Middle_Finger_Proximal",
102 , m_received_package_count(0)
128 "Connect finished " << ((success) ?
"succesfully" :
"with an error"));
141 "Disconnect called, disabling all channels and closing interface...");
168 ab << control_command;
174 "Control command was given for channel: " 175 << channel <<
"Driving motor to position: " << position);
180 "Control command was given for unknown (or all) channel: " 181 << channel <<
"- ignoring request");
192 ab << control_command;
198 "Control command was given for all channels: Driving motors to positions: " 199 << positions[0] <<
" , " << positions[1] <<
" , " << positions[2]
200 <<
" , " << positions[3] <<
" , " << positions[4] <<
" , " 201 << positions[5] <<
" , " << positions[6] <<
" , " << positions[7]
202 <<
" , " << positions[8] <<
" , ");
212 "Control command was given for all channels but with to few points. Expected at least " 213 <<
SVH_DIMENSION <<
" values but only got " << positions.size()
214 <<
"use the individual setTarget function for this");
230 "Enable was called and no channel was previously activated, commands are " 231 "sent individually......");
233 "Sending pwm_fault and pwm_otw...(0x001F) to reset software warnings");
236 controller_state.
pwm_otw = 0x001F;
237 ab << controller_state;
244 std::this_thread::sleep_for(std::chrono::microseconds(2000));
247 "Enabling 12V Driver (pwm_reset and pwm_active = 0x0200)...");
249 controller_state.pwm_reset = 0x0200;
250 controller_state.pwm_active = 0x0200;
251 ab << controller_state;
256 std::this_thread::sleep_for(std::chrono::microseconds(2000));
260 controller_state.pos_ctrl = 0x0001;
261 controller_state.cur_ctrl = 0x0001;
262 ab << controller_state;
267 std::this_thread::sleep_for(std::chrono::microseconds(2000));
285 controller_state.
pwm_otw = 0x001F;
288 ab << controller_state;
294 std::this_thread::sleep_for(std::chrono::microseconds(500));
296 controller_state.pos_ctrl = 0x0001;
297 controller_state.cur_ctrl = 0x0001;
298 ab << controller_state;
308 "Activation request for ALL or unknown channel: " << channel
309 <<
"- ignoring request");
329 controller_state.
pwm_otw = 0x001F;
332 ab << controller_state;
341 controller_state.
pwm_otw = 0x001F;
353 ab << controller_state;
362 "Disable was requestet for unknown channel: " << channel
363 <<
"- ignoring request");
369 "Disabling Channel not possible. Serial interface is not connected!");
390 "Controller feedback was requested for channel: " << channel);
404 "Controller feedback was requestet for unknown channel: " << channel <<
"- ignoring request");
411 "Requesting PositionSettings from Hardware for channel: " << channel);
425 ab << position_settings;
433 "Position controller settings where send to change channel: " << channel
436 "wmn " << position_settings.wmn <<
" " 437 <<
"wmx " << position_settings.wmx <<
" " 438 <<
"dwmx " << position_settings.dwmx <<
" " 439 <<
"ky " << position_settings.ky <<
" " 440 <<
"dt " << position_settings.dt <<
" " 441 <<
"imn " << position_settings.imn <<
" " 442 <<
"imx " << position_settings.imx <<
" " 443 <<
"kp " << position_settings.kp <<
" " 444 <<
"ki " << position_settings.ki <<
" " 445 <<
"kd " << position_settings.kd <<
" ");
450 "Position controller settings where given for unknown channel: " 451 << channel <<
"- ignoring request");
469 "Get Current Settings can only be requested with a specific channel, ALL or unknown channel:" 470 << channel <<
"was selected ");
481 ab << current_settings;
489 "Current controller settings where send to change channel: " << channel
492 "wmn " << current_settings.wmn <<
" " 493 <<
"wmx " << current_settings.wmx <<
" " 494 <<
"ky " << current_settings.ky <<
" " 495 <<
"dt " << current_settings.dt <<
" " 496 <<
"imn " << current_settings.imn <<
" " 497 <<
"imx " << current_settings.imx <<
" " 498 <<
"kp " << current_settings.kp <<
" " 499 <<
"ki " << current_settings.ki <<
" " 500 <<
"umn " << current_settings.umn <<
" " 501 <<
"umx " << current_settings.umx);
506 "Current controller settings where given for unknown channel: " 507 << channel <<
"- ignoring request");
521 for (
size_t i = 0; i < encoder_settings.
scalings.size(); i++)
525 "[" << (
int)i <<
"] " 526 <<
": " << encoder_settings.
scalings[i] <<
" ");
531 ab << encoder_settings;
550 uint8_t channel = (packet.
address >> 4) & 0x0F;
570 "Received a Control Feedback/Control Command packet for channel " 572 <<
" Position: " << (
int)m_controller_feedback[channel].position
573 <<
" Current: " << (
int)m_controller_feedback[channel].current);
579 "Received a Control Feedback/Control Command packet for ILLEGAL channel " 580 << channel <<
"- packet ignored!");
593 "Received a Control Feedback/Control Command packet for channel all channels ");
603 "Received a get/set position setting packet for channel " << channel);
605 "wmn " << m_position_settings[channel].wmn <<
" " 606 <<
"wmx " << m_position_settings[channel].wmx <<
" " 607 <<
"dwmx " << m_position_settings[channel].dwmx <<
" " 608 <<
"ky " << m_position_settings[channel].ky <<
" " 609 <<
"dt " << m_position_settings[channel].dt <<
" " 610 <<
"imn " << m_position_settings[channel].imn <<
" " 611 <<
"imx " << m_position_settings[channel].imx <<
" " 612 <<
"kp " << m_position_settings[channel].kp <<
" " 613 <<
"ki " << m_position_settings[channel].ki <<
" " 614 <<
"kd " << m_position_settings[channel].kd);
619 "Received a get/set position setting packet for ILLEGAL channel " 620 << channel <<
"- packet ignored!");
631 "Received a get/set current setting packet for channel " << channel);
633 "wmn " << m_current_settings[channel].wmn <<
" " 634 <<
"wmx " << m_current_settings[channel].wmx <<
" " 635 <<
"ky " << m_current_settings[channel].ky <<
" " 636 <<
"dt " << m_current_settings[channel].dt <<
" " 637 <<
"imn " << m_current_settings[channel].imn <<
" " 638 <<
"imx " << m_current_settings[channel].imx <<
" " 639 <<
"kp " << m_current_settings[channel].kp <<
" " 640 <<
"ki " << m_current_settings[channel].ki <<
" " 641 <<
"umn " << m_current_settings[channel].umn <<
" " 642 <<
"umx " << m_current_settings[channel].umx <<
" ");
647 "Received a get/set current setting packet for ILLEGAL channel " 648 << channel <<
"- packet ignored!");
660 "Controllerstate (NO HEX):" 662 <<
"0x" << static_cast<int>(m_controller_state.pwm_fault) <<
" " 664 <<
"0x" << static_cast<int>(m_controller_state.pwm_otw) <<
" " 666 <<
"0x" << static_cast<int>(m_controller_state.pwm_reset) <<
" " 668 <<
"0x" << static_cast<int>(m_controller_state.pwm_active) <<
" " 670 <<
"0x" << static_cast<int>(m_controller_state.pos_ctrl) <<
" " 672 <<
"0x" << static_cast<int>(m_controller_state.cur_ctrl));
684 "Hardware is using the following Firmware: " 685 << m_firmware_info.svh <<
" Version: " << m_firmware_info.version_major
686 <<
"." << m_firmware_info.version_minor <<
" : " 687 << m_firmware_info.text);
691 "Received a Packet with unknown address: " << (packet.
address & 0x0F)
692 <<
" - ignoring packet");
708 "GetFeedback was requested for unknown channel: " << channel
709 <<
"- ignoring request");
732 "GetPositionSettings was requested for unknown channel: " << channel <<
"- ignoring request");
749 "GetCurrentSettings was requested for unknown channel: " << channel <<
"- ignoring request");
776 "Request for transmit packet count could not be answered as the device is " 777 "not connected - ignoring request");
SVHFirmwareInfo getFirmwareInfo()
get the latest stored Firmware information from the controller (NOT THE HARDWARE) ...
void requestPositionSettings(const SVHChannel &channel)
request the settings of the position controller for a specific channel
const uint8_t SVH_GET_POSITION_SETTINGS
Requests the active settings of the position controller.
uint16_t pos_ctrl
Enable/Disable of position controller (0x0001 to Activate )
void disableChannel(const SVHChannel &channel)
Disable one or all motor channels.
SVHFirmwareInfo m_firmware_info
Latest firmware info.
Structure for transmitting all controllcommands at once.
std::vector< SVHCurrentSettings > m_current_settings
vector of current controller parameters for each finger
SVHEncoderSettings m_encoder_settings
Currently active encoder settings.
void resetPackageCounts()
resetPackageCounts sets the sent and reveived package counts to zero
void setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings)
activate a new set of position controller settings for a specific channel
const uint8_t SVH_GET_CONTROL_FEEDBACK
Request the position and current of a channel to be sent.
unsigned int transmittedPacketCount()
get number of transmitted packets
unsigned int getSentPackageCount()
requests the number of sent packages. Request ist transferred to the serial interface that knows abou...
void receivedPacketCallback(const SVHSerialPacket &packet, unsigned int packet_count)
callback function for interpretation of packages
void getControllerFeedbackAllChannels(SVHControllerFeedbackAllChannels &controller_feedback)
Get all currently available controllerfeedbacks.
The SVHCurrentSettings save the current controller paramters for a single motor.
const uint8_t SVH_SET_CONTROL_COMMAND
Sets the target position of a channel.
#define SVH_LOG_INFO_STREAM(NAME, M)
static const float CHANNEL_EFFORT_CONSTANTS[9][2]
Effort multipliers to calculate the torque of the motors for the individual channels.
const uint8_t SVH_SET_ENCODER_VALUES
Set new encoder scalings.
uint16_t version_minor
Minor version number.
uint8_t address
Adress denotes the actual function of the package.
void close()
canceling receive thread and closing connection to serial port
bool getControllerFeedback(const SVHChannel &channel, SVHControllerFeedback &controller_feedback)
request the latest stored controllerfeedback (current, position) from the controller.
std::vector< uint8_t > array
array of template type TArray
bool connect(const std::string &dev_name)
Open serial device connection.
const uint8_t SVH_GET_CONTROLLER_STATE
Requests the state of the controller (active,faults,enabled channels)
unsigned int getReceivedPackageCount()
request the number of correctly received packages. This number is refreshed every time the serialinte...
std::vector< uint32_t > scalings
encoderSettings consist of multipliers for each encoder
void requestControllerState()
Request current controller state (mainly usefull for debug purposes)
std::vector< SVHControllerFeedback > feedbacks
Vector holding multiple channels.
bool sendPacket(SVHSerialPacket &packet)
function for sending packets via serial device to the SVH
unsigned int m_received_package_count
std::vector< uint8_t > data
Payload of the package.
void setControllerTarget(const SVHChannel &channel, const int32_t &position)
Set new position target for finger index.
bool connect(const std::string &dev_name)
connecting to serial device and starting receive thread
std::vector< SVHControllerFeedback > m_controller_feedback
ControllerFeedback indicates current position and current per finger.
const uint8_t SVH_SET_CONTROLLER_STATE
Sets new controller states (enable channels, clear faults)
bool isEnabled(const SVHChannel &channel)
Check if a channel was enabled.
#define SVH_LOG_DEBUG_STREAM(NAME, M)
const uint8_t SVH_GET_ENCODER_VALUES
Request the current encoder scalings.
#define SVH_LOG_ERROR_STREAM(NAME, M)
void requestControllerFeedback(const SVHChannel &channel)
request feedback (position and current) to a specific channel
void setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings ¤t_settings)
activate a new set of current controller settings for a specific channel
void receivedPacketCallback(const SVHSerialPacket &packet, unsigned int packet_count)
The SVHFirmwareInfo holds the data of a firmware response from the hardware.
The SVHControllerFeedback saves the feedback of a single motor.
const uint8_t SVH_SET_CURRENT_SETTINGS
Sets new settings for the current controller.
void disconnect()
disconnect serial device
ControlCommands are given as a single target position for the position controller (given in ticks) ...
void appendWithoutConversion(const T &data)
add data without any byte conversion
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
request the latest stored positionsettings from the controller
uint16_t version_major
Major version number.
uint16_t cur_ctrl
Enable/Disbale of current controller (0x0001 to Activate)
const uint8_t SVH_SET_POSITION_SETTINGS
Sets new settings for the position controller.
static const char * m_channel_description[]
Description values to get the corresponding string value to a channel enum.
std::vector< SVHPositionSettings > m_position_settings
vector of position controller parameters for each finger
const uint8_t SVH_GET_CURRENT_SETTINGS
Requests the active settings of the current controller.
SVHController()
Constructs a controller class for the SCHUNK five finger hand.
bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings ¤t_settings)
request the latest stored currentsettings from the controller
This class controls the the SCHUNK five finger hand.
void setControllerTargetAllChannels(const std::vector< int32_t > &positions)
Setting new position controller target for all fingers.
SVHControllerState m_controller_state
Currently active controllerstate on the HW Controller (indicates if PWM active etc.)
The SVHPositionSettings save the position controller paramters for a single motor.
SVHSerialInterface * m_serial_interface
Serial interface for transmission and reveibing of data packets.
void reset(size_t array_size=1)
Resets the Arraybuilder to initial state, all values will be deleted.
The SVHControllerState indicates the current state of the MeCoVis controller IC which is used in the ...
const uint8_t SVH_GET_CONTROL_FEEDBACK_ALL
Requests the positions and currents of ALL channels.
const uint8_t SVH_SET_CONTROL_COMMAND_ALL
Sends the target position to ALL the channels.
uint16_t m_enable_mask
Bitmask to tell which fingers are enabled.
The SVHControllerFeedbackAllChannes saves the feedback of a all motors.
const uint8_t SVH_GET_FIRMWARE_INFO
Request the firmware info to be transmitted.
Basic communication handler for the SCHUNK five finger hand.
void resetTransmitPackageCount()
resetTransmitPackageCount Resets the transmitpackage count to zero
void requestEncoderValues()
read out the mutipliers for the encoders from the hardware
void requestCurrentSettings(const SVHChannel &channel)
request the settings of the current controller for a specific channel
bool isConnected()
returns connected state of serial device
#define SVH_LOG_WARN_STREAM(NAME, M)
The SVHEncoderSettings hold the settings for the encoder scaling of each channel. ...
void setEncoderValues(const SVHEncoderSettings &encoder_settings)
sends a new set of encodervalues to the hardware
The SerialPacket holds the (non generated) header and data of one message to the SVH-Hardware.
void requestFirmwareInfo()
request a transmission of formware information
void enableChannel(const SVHChannel &channel)
Enable one or all motor channels.