30 #include <std_msgs/Int8.h>    31 #include <std_msgs/Empty.h>    32 #include <sensor_msgs/JointState.h>    33 #include "std_msgs/MultiArrayLayout.h"    34 #include "std_msgs/MultiArrayDimension.h"    35 #include "std_msgs/Float64MultiArray.h"    38 #include <dynamic_reconfigure/server.h>    39 #include <schunk_svh_driver/svhConfig.h>    46 #include <boost/shared_ptr.hpp>   107 #endif // S5FH_CONTROLLER_H std_msgs::Float64MultiArray getChannelCurrents()
getChannelCurrents Returns the current values of the channels as raw output 
 
SVHNode(const ros::NodeHandle &nh)
SVHNode constructs a new node object that handles most of the functionality. 
 
std::string serial_device_name_
Serial device to use for communication with hardware. 
 
void enableChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to enable channels of SCHUNK five finger hand. 
 
void jointStateCallback(const sensor_msgs::JointStateConstPtr &input)
Callback function for setting channel target positions to SCHUNK five finger hand. 
 
void dynamic_reconfigure_callback(svh_controller::svhConfig &config, uint32_t level)
Dynamic reconfigure callback to update changing parameters. 
 
void resetChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to reset/home channels of SCHUNK five finger hand. 
 
std_msgs::Float64MultiArray channel_currents
Current Value message template. 
 
std::string name_prefix
Prefix for the driver to identify joint names if the Driver should expext "left_hand_Pinky" than the ...
 
int connect_retry_count
Number of times the connect routine tries to connect in case that we receive at least one package...
 
sensor_msgs::JointState getChannelFeedback()
SVHNode::getChannelFeedback Gets the latest received positions and efforts from the driver...
 
sensor_msgs::JointState channel_pos_
joint state message template 
 
void connectCallback(const std_msgs::Empty &)
Callback function for connecting to SCHUNK five finger hand. 
 
boost::shared_ptr< driver_svh::SVHFingerManager > fm_
Handle to the SVH finger manager for library access.