#include <SVHNode.h>
Definition at line 48 of file SVHNode.h.
SVHNode constructs a new node object that handles most of the functionality.
- Parameters
-
Definition at line 39 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
- Returns
- Array containing the current values of the channels in mA
Definition at line 366 of file SVHNode.cpp.
sensor_msgs::JointState SVHNode::getChannelFeedback |
( |
| ) |
|
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 |
Current Value message template.
Definition at line 104 of file SVHNode.h.
sensor_msgs::JointState SVHNode::channel_pos_ |
|
private |
joint state message template
Definition at line 101 of file SVHNode.h.
int SVHNode::connect_retry_count |
|
private |
Number of times the connect routine tries to connect in case that we receive at least one package.
Definition at line 95 of file SVHNode.h.
Handle to the SVH finger manager for library access.
Definition at line 89 of file SVHNode.h.
std::string SVHNode::name_prefix |
|
private |
Prefix for the driver to identify joint names if the Driver should expext "left_hand_Pinky" than the prefix is left_hand.
Definition at line 98 of file SVHNode.h.
std::string SVHNode::serial_device_name_ |
|
private |
Serial device to use for communication with hardware.
Definition at line 92 of file SVHNode.h.
The documentation for this class was generated from the following files: