#include <SVHNode.h>
Public Member Functions | |
| void | connectCallback (const std_msgs::Empty &) |
| Callback function for connecting to SCHUNK five finger hand. | |
| void | dynamic_reconfigure_callback (svh_controller::svhConfig &config, uint32_t level) |
| Dynamic reconfigure callback to update changing parameters. | |
| void | enableChannelCallback (const std_msgs::Int8ConstPtr &channel) |
| Callback function to enable channels of SCHUNK five finger hand. | |
| std_msgs::Float64MultiArray | getChannelCurrents () |
| getChannelCurrents Returns the current values of the channels as raw output | |
| sensor_msgs::JointState | getChannelFeedback () |
| SVHNode::getChannelFeedback Gets the latest received positions and efforts from the driver. | |
| void | jointStateCallback (const sensor_msgs::JointStateConstPtr &input) |
| Callback function for setting channel target positions to SCHUNK five finger hand. | |
| void | resetChannelCallback (const std_msgs::Int8ConstPtr &channel) |
| Callback function to reset/home channels of SCHUNK five finger hand. | |
| SVHNode (const ros::NodeHandle &nh) | |
| SVHNode constructs a new node object that handles most of the functionality. | |
| ~SVHNode () | |
| Default DTOR. | |
Private Attributes | |
| std_msgs::Float64MultiArray | channel_currents |
| Current Value message template. | |
| sensor_msgs::JointState | channel_pos_ |
| joint state message template | |
| int | connect_retry_count |
| Number of times the connect routine tries to connect in case that we receive at least one package. | |
| boost::shared_ptr < driver_svh::SVHFingerManager > | fm_ |
| Handle to the SVH finger manager for library access. | |
| std::string | name_prefix |
| Prefix for the driver to identify joint names if the Driver should expext "left_hand_Pinky" than the prefix is left_hand. | |
| std::string | serial_device_name_ |
| Serial device to use for communication with hardware. | |
| SVHNode::SVHNode | ( | const ros::NodeHandle & | nh | ) |
SVHNode constructs a new node object that handles most of the functionality.
| nh | ROS Nodehandle |
Definition at line 39 of file SVHNode.cpp.
Default DTOR.
Definition at line 213 of file SVHNode.cpp.
| void SVHNode::connectCallback | ( | const std_msgs::Empty & | ) |
Callback function for connecting to SCHUNK five finger hand.
Definition at line 229 of file SVHNode.cpp.
| void SVHNode::dynamic_reconfigure_callback | ( | svh_controller::svhConfig & | config, |
| uint32_t | level | ||
| ) |
Dynamic reconfigure callback to update changing parameters.
Definition at line 220 of file SVHNode.cpp.
| void SVHNode::enableChannelCallback | ( | const std_msgs::Int8ConstPtr & | channel | ) |
Callback function to enable channels of SCHUNK five finger hand.
Definition at line 262 of file SVHNode.cpp.
| std_msgs::Float64MultiArray SVHNode::getChannelCurrents | ( | ) |
getChannelCurrents Returns the current values of the channels as raw output
Definition at line 366 of file SVHNode.cpp.
| sensor_msgs::JointState SVHNode::getChannelFeedback | ( | ) |
SVHNode::getChannelFeedback Gets the latest received positions and efforts from the driver.
Definition at line 341 of file SVHNode.cpp.
| void SVHNode::jointStateCallback | ( | const sensor_msgs::JointStateConstPtr & | input | ) |
Callback function for setting channel target positions to SCHUNK five finger hand.
Definition at line 268 of file SVHNode.cpp.
| void SVHNode::resetChannelCallback | ( | const std_msgs::Int8ConstPtr & | channel | ) |
Callback function to reset/home channels of SCHUNK five finger hand.
Definition at line 246 of file SVHNode.cpp.
std_msgs::Float64MultiArray SVHNode::channel_currents [private] |
sensor_msgs::JointState SVHNode::channel_pos_ [private] |
int SVHNode::connect_retry_count [private] |
boost::shared_ptr<driver_svh::SVHFingerManager> SVHNode::fm_ [private] |
std::string SVHNode::name_prefix [private] |
std::string SVHNode::serial_device_name_ [private] |