#include <SVHWrapper.h>
|
| bool | connect () |
| | load parameters and try connecting More...
|
| |
| void | connectCallback (const std_msgs::Empty &) |
| | Callback function for connecting to SCHUNK five finger hand. More...
|
| |
| void | enableChannelCallback (const std_msgs::Int8ConstPtr &channel) |
| | Callback function to enable channels of SCHUNK five finger hand. More...
|
| |
| bool | homeAllNodes (schunk_svh_msgs::HomeAllRequest &req, schunk_svh_msgs::HomeAllResponse &resp) |
| |
| bool | homeNodesChannelIds (schunk_svh_msgs::HomeWithChannelsRequest &req, schunk_svh_msgs::HomeWithChannelsResponse &resp) |
| |
| void | initControllerParameters (const uint16_t manual_major_version, const uint16_t manual_minor_version) |
| |
| void | resetChannelCallback (const std_msgs::Int8ConstPtr &channel) |
| | Callback function to reset/home channels of SCHUNK five finger hand. More...
|
| |
| bool | setAllForceLimits (schunk_svh_msgs::SetAllChannelForceLimits::Request &req, schunk_svh_msgs::SetAllChannelForceLimits::Response &res) |
| |
| float | setChannelForceLimit (size_t channel, float force_limit) |
| |
| bool | setForceLimitById (schunk_svh_msgs::SetChannelForceLimit::Request &req, schunk_svh_msgs::SetChannelForceLimit::Response &res) |
| |
| void | setRosControlEnable (bool enable) |
| | function to set the ros-control-loop enabling flag from the diagnostics class More...
|
| |
Definition at line 53 of file SVHWrapper.h.
◆ SVHWrapper()
◆ ~SVHWrapper()
| SVHWrapper::~SVHWrapper |
( |
| ) |
|
◆ channelsEnabled()
| bool SVHWrapper::channelsEnabled |
( |
| ) |
|
|
inline |
◆ connect()
| bool SVHWrapper::connect |
( |
| ) |
|
|
private |
◆ connectCallback()
| void SVHWrapper::connectCallback |
( |
const std_msgs::Empty & |
| ) |
|
|
private |
Callback function for connecting to SCHUNK five finger hand.
Definition at line 256 of file SVHWrapper.cpp.
◆ enableChannelCallback()
| void SVHWrapper::enableChannelCallback |
( |
const std_msgs::Int8ConstPtr & |
channel | ) |
|
|
private |
Callback function to enable channels of SCHUNK five finger hand.
Definition at line 263 of file SVHWrapper.cpp.
◆ getFingerManager()
◆ getNamePrefix()
| std::string SVHWrapper::getNamePrefix |
( |
| ) |
const |
|
inline |
◆ homeAllNodes()
| bool SVHWrapper::homeAllNodes |
( |
schunk_svh_msgs::HomeAllRequest & |
req, |
|
|
schunk_svh_msgs::HomeAllResponse & |
resp |
|
) |
| |
|
private |
◆ homeNodesChannelIds()
| bool SVHWrapper::homeNodesChannelIds |
( |
schunk_svh_msgs::HomeWithChannelsRequest & |
req, |
|
|
schunk_svh_msgs::HomeWithChannelsResponse & |
resp |
|
) |
| |
|
private |
◆ initControllerParameters()
| void SVHWrapper::initControllerParameters |
( |
const uint16_t |
manual_major_version, |
|
|
const uint16_t |
manual_minor_version |
|
) |
| |
|
private |
◆ resetChannelCallback()
| void SVHWrapper::resetChannelCallback |
( |
const std_msgs::Int8ConstPtr & |
channel | ) |
|
|
private |
Callback function to reset/home channels of SCHUNK five finger hand.
◆ setAllForceLimits()
| bool SVHWrapper::setAllForceLimits |
( |
schunk_svh_msgs::SetAllChannelForceLimits::Request & |
req, |
|
|
schunk_svh_msgs::SetAllChannelForceLimits::Response & |
res |
|
) |
| |
|
private |
◆ setChannelForceLimit()
| float SVHWrapper::setChannelForceLimit |
( |
size_t |
channel, |
|
|
float |
force_limit |
|
) |
| |
|
private |
◆ setForceLimitById()
| bool SVHWrapper::setForceLimitById |
( |
schunk_svh_msgs::SetChannelForceLimit::Request & |
req, |
|
|
schunk_svh_msgs::SetChannelForceLimit::Response & |
res |
|
) |
| |
|
private |
◆ setRosControlEnable()
| void SVHWrapper::setRosControlEnable |
( |
bool |
enable | ) |
|
|
private |
function to set the ros-control-loop enabling flag from the diagnostics class
Definition at line 136 of file SVHWrapper.cpp.
◆ connect_sub
◆ enable_sub
◆ m_channels_enabled
| bool SVHWrapper::m_channels_enabled |
|
private |
m_channels_enabled enables the ros-control-loop in the hw interface
Definition at line 126 of file SVHWrapper.h.
◆ m_connect_retry_count
| int SVHWrapper::m_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 114 of file SVHWrapper.h.
◆ m_finger_manager
Handle to the SVH finger manager for library access.
Definition at line 85 of file SVHWrapper.h.
◆ m_firmware_major_version
| int SVHWrapper::m_firmware_major_version |
|
private |
firmware version, as read from the firmware or set by config. If version is 0, it hasn't been read yet.
Definition at line 122 of file SVHWrapper.h.
◆ m_firmware_minor_version
| int SVHWrapper::m_firmware_minor_version |
|
private |
◆ m_home_service_all
◆ m_home_service_joint_names
◆ m_name_prefix
| std::string SVHWrapper::m_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 118 of file SVHWrapper.h.
◆ m_priv_nh
◆ m_serial_device_name
| std::string SVHWrapper::m_serial_device_name |
|
private |
Serial device to use for communication with hardware.
Definition at line 91 of file SVHWrapper.h.
◆ m_setAllForceLimits_srv
◆ m_setForceLimitById_srv
◆ m_svh_diagnostics
Handle to the diagnostics test class creating a test protocol with the web gui package.
Definition at line 88 of file SVHWrapper.h.
The documentation for this class was generated from the following files: