42 #include <icl_comm/ByteOrderConversion.h> 43 #include <boost/bind/bind.hpp> 45 using icl_comm::ArrayBuilder;
54 "Index_Finger_Distal",
55 "Index_Finger_Proximal",
56 "Middle_Finger_Distal",
57 "Middle_Finger_Proximal",
83 m_received_package_count(0)
138 ab << control_command;
139 serial_packet.
data = ab.array;
158 ab << control_command;
159 serial_packet.
data = ab.array;
170 LOGGING_WARNING_C(DriverSVH,
SVHController,
"Control command was given for all channels but with to few points. Expected at least "<<
eSVH_DIMENSION <<
" values but only got " << positions.size() <<
"use the individual setTarget function for this" <<
endl);
189 controller_state.
pwm_otw = 0x001F;
190 ab << controller_state;
191 serial_packet.
data = ab.array;
200 controller_state.pwm_reset = 0x0200;
201 controller_state.pwm_active = 0x0200;
202 ab << controller_state;
203 serial_packet.
data = ab.array;
211 controller_state.pos_ctrl = 0x0001;
212 controller_state.cur_ctrl = 0x0001;
213 ab << controller_state;
214 serial_packet.
data = ab.array;
235 controller_state.
pwm_otw = 0x001F;
238 ab << controller_state;
239 serial_packet.
data = ab.array;
246 controller_state.pos_ctrl = 0x0001;
247 controller_state.cur_ctrl = 0x0001;
248 ab << controller_state;
249 serial_packet.
data = ab.array;
278 controller_state.
pwm_otw = 0x001F;
281 ab << controller_state;
282 serial_packet.
data = ab.array;
290 controller_state.
pwm_otw = 0x001F;
302 ab << controller_state;
303 serial_packet.
data = ab.array;
364 ab << position_settings;
365 serial_packet.
data = ab.array;
372 LOGGING_DEBUG_C(DriverSVH,
SVHController,
"wmn " << position_settings.wmn <<
" " <<
"wmx " << position_settings.wmx <<
" " <<
"dwmx "<< position_settings.dwmx <<
" " 373 <<
"ky " << position_settings.ky <<
" " <<
"dt " << position_settings.dt <<
" " <<
"imn " << position_settings.imn <<
" " 374 <<
"imx " << position_settings.imx <<
" " <<
"kp " << position_settings.kp <<
" " <<
"ki " << position_settings.ki <<
" " 375 <<
"kd " << position_settings.kd <<
" " <<
endl );
395 LOGGING_WARNING_C(DriverSVH,
SVHController,
"Get Current Settings can only be requested with a specific channel, ALL or unknown channel:" << channel <<
"was selected " <<
endl);
405 ab << current_settings;
406 serial_packet.
data = ab.array;
413 LOGGING_DEBUG_C(DriverSVH,
SVHController,
"wmn "<< current_settings.wmn <<
" " <<
"wmx "<< current_settings.wmx <<
" " <<
"ky " << current_settings.ky <<
" " 414 <<
"dt " << current_settings.dt <<
" " <<
"imn "<< current_settings.imn <<
" " <<
"imx "<< current_settings.imx <<
" " 415 <<
"kp " << current_settings.kp <<
" " <<
"ki " << current_settings.ki <<
" " <<
"umn "<< current_settings.umn <<
" " 416 <<
"umx "<< current_settings.umx <<
endl);
435 for (
size_t i = 0; i < encoder_settings.
scalings.size(); i++)
444 ab << encoder_settings;
445 serial_packet.
data = ab.array;
466 ab.appendWithoutConversion(packet.
data);
486 LOGGING_ERROR_C(DriverSVH,
SVHController,
"Received a Control Feedback/Control Command packet for ILLEGAL channel "<< channel <<
"- packet ignored!" <<
endl);
505 LOGGING_TRACE_C(DriverSVH,
SVHController,
"wmn " << m_position_settings[channel].wmn <<
" "<<
"wmx " << m_position_settings[channel].wmx <<
" "<<
"dwmx "<< m_position_settings[channel].dwmx <<
" "<<
"ky " << m_position_settings[channel].ky <<
" "<<
"dt " << m_position_settings[channel].dt <<
" "<<
"imn " << m_position_settings[channel].imn <<
" "<<
"imx " << m_position_settings[channel].imx <<
" " <<
"kp " << m_position_settings[channel].kp <<
" " <<
"ki " << m_position_settings[channel].ki <<
" " <<
"kd " << m_position_settings[channel].kd <<
endl);
520 LOGGING_TRACE_C(DriverSVH,
SVHController,
"wmn "<< m_current_settings[channel].wmn <<
" " <<
"wmx "<< m_current_settings[channel].wmx <<
" " <<
"ky " << m_current_settings[channel].ky <<
" " <<
"dt " << m_current_settings[channel].dt <<
" " <<
"imn "<< m_current_settings[channel].imn <<
" " <<
"imx "<< m_current_settings[channel].imx <<
" " <<
"kp " << m_current_settings[channel].kp <<
" " <<
"ki " << m_current_settings[channel].ki <<
" " <<
"umn "<< m_current_settings[channel].umn <<
" " <<
"umx "<< m_current_settings[channel].umx <<
" "<<
endl);
533 LOGGING_TRACE_C(DriverSVH,
SVHController,
"Controllerstate (NO HEX):" <<
"pwm_fault " <<
"0x" << static_cast<int>(m_controller_state.pwm_fault) <<
" " <<
"pwm_otw " <<
"0x" << static_cast<int>(m_controller_state.pwm_otw) <<
" " <<
"pwm_reset " <<
"0x" << static_cast<int>(m_controller_state.pwm_reset) <<
" " <<
"pwm_active " <<
"0x" << static_cast<int>(m_controller_state.pwm_active) <<
" " <<
"pos_ctr " <<
"0x" << static_cast<int>(m_controller_state.pos_ctrl) <<
" " <<
"cur_ctrl " <<
"0x" << static_cast<int>(m_controller_state.cur_ctrl) <<
endl);
543 LOGGING_INFO(DriverSVH,
"Hardware is using the following Firmware: " );
544 LOGGING_INFO(DriverSVH, m_firmware_info.svh <<
" Version: " << m_firmware_info.version_major <<
"." << m_firmware_info.version_minor <<
" : " << m_firmware_info.text <<
endl);
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...
#define LOGGING_INFO(streamname, arg)
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.
const uint8_t SVH_SET_ENCODER_VALUES
Set new encoder scalings.
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.
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)
#define LOGGING_WARNING_C(streamname, classname, arg)
int usleep(unsigned long useconds)
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
store how many packages where actually received. Updated every time the receivepacket callback is cal...
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
#define LOGGING_DEBUG_C(streamname, classname, arg)
std::vector< SVHControllerFeedback > m_controller_feedback
ControllerFeedback indicates current position and current per finger.
ThreadStream & endl(ThreadStream &stream)
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.
const uint8_t SVH_GET_ENCODER_VALUES
Request the current encoder scalings.
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
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) ...
bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings)
request the latest stored positionsettings from the controller
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.
static const float channel_effort_constants[9]
Effort multipliers to calculate the torque of the motors for the individual channels.
SVHSerialInterface * m_serial_interface
Serial interface for transmission and reveibing of data packets.
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
#define LOGGING_TRACE_C(streamname, classname, arg)
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
The SVHEncoderSettings hold the settings for the encoder scaling of each channel. ...
SVHChannel
Channel indicates which motor to use in command calls. WARNING: DO NOT CHANGE THE ORDER OF THESE as i...
#define LOGGING_ERROR_C(streamname, classname, arg)
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.
uint16_t pwm_reset
Bitmask for low-active resets of the channels (0-8). Channel 9 (0x0200) is a special channel that act...
void requestFirmwareInfo()
request a transmission of formware information
void enableChannel(const SVHChannel &channel)
Enable one or all motor channels.