Public Member Functions | Private Member Functions | Private Attributes | List of all members
SVHWrapper Class Reference

#include <SVHWrapper.h>

Public Member Functions

bool channelsEnabled ()
 
std::shared_ptr< driver_svh::SVHFingerManagergetFingerManager () const
 
std::string getNamePrefix () const
 
 SVHWrapper (const ros::NodeHandle &nh)
 
 ~SVHWrapper ()
 

Private Member Functions

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...
 

Private Attributes

ros::Subscriber connect_sub
 
ros::Subscriber enable_sub
 
bool m_channels_enabled
 m_channels_enabled enables the ros-control-loop in the hw interface More...
 
int m_connect_retry_count
 
std::shared_ptr< driver_svh::SVHFingerManagerm_finger_manager
 Handle to the SVH finger manager for library access. More...
 
int m_firmware_major_version
 
int m_firmware_minor_version
 
ros::ServiceServer m_home_service_all
 
ros::ServiceServer m_home_service_joint_names
 
std::string m_name_prefix
 
ros::NodeHandle m_priv_nh
 private node handle More...
 
std::string m_serial_device_name
 Serial device to use for communication with hardware. More...
 
ros::ServiceServer m_setAllForceLimits_srv
 
ros::ServiceServer m_setForceLimitById_srv
 
std::shared_ptr< SVHDiagnosticsm_svh_diagnostics
 Handle to the diagnostics test class creating a test protocol with the web gui package. More...
 

Detailed Description

Definition at line 53 of file SVHWrapper.h.

Constructor & Destructor Documentation

◆ SVHWrapper()

SVHWrapper::SVHWrapper ( const ros::NodeHandle nh)

Definition at line 39 of file SVHWrapper.cpp.

◆ ~SVHWrapper()

SVHWrapper::~SVHWrapper ( )

Definition at line 201 of file SVHWrapper.cpp.

Member Function Documentation

◆ channelsEnabled()

bool SVHWrapper::channelsEnabled ( )
inline

Definition at line 66 of file SVHWrapper.h.

◆ connect()

bool SVHWrapper::connect ( )
private

load parameters and try connecting

Definition at line 207 of file SVHWrapper.cpp.

◆ 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()

std::shared_ptr<driver_svh::SVHFingerManager> SVHWrapper::getFingerManager ( ) const
inline

Definition at line 59 of file SVHWrapper.h.

◆ getNamePrefix()

std::string SVHWrapper::getNamePrefix ( ) const
inline

Definition at line 64 of file SVHWrapper.h.

◆ homeAllNodes()

bool SVHWrapper::homeAllNodes ( schunk_svh_msgs::HomeAllRequest &  req,
schunk_svh_msgs::HomeAllResponse &  resp 
)
private

Definition at line 268 of file SVHWrapper.cpp.

◆ homeNodesChannelIds()

bool SVHWrapper::homeNodesChannelIds ( schunk_svh_msgs::HomeWithChannelsRequest &  req,
schunk_svh_msgs::HomeWithChannelsResponse &  resp 
)
private

Definition at line 286 of file SVHWrapper.cpp.

◆ initControllerParameters()

void SVHWrapper::initControllerParameters ( const uint16_t  manual_major_version,
const uint16_t  manual_minor_version 
)
private

Definition at line 141 of file SVHWrapper.cpp.

◆ 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

Definition at line 323 of file SVHWrapper.cpp.

◆ setChannelForceLimit()

float SVHWrapper::setChannelForceLimit ( size_t  channel,
float  force_limit 
)
private

Definition at line 341 of file SVHWrapper.cpp.

◆ setForceLimitById()

bool SVHWrapper::setForceLimitById ( schunk_svh_msgs::SetChannelForceLimit::Request &  req,
schunk_svh_msgs::SetChannelForceLimit::Response &  res 
)
private

Definition at line 333 of file SVHWrapper.cpp.

◆ 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.

Member Data Documentation

◆ connect_sub

ros::Subscriber SVHWrapper::connect_sub
private

Definition at line 128 of file SVHWrapper.h.

◆ enable_sub

ros::Subscriber SVHWrapper::enable_sub
private

Definition at line 129 of file SVHWrapper.h.

◆ 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

std::shared_ptr<driver_svh::SVHFingerManager> SVHWrapper::m_finger_manager
private

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

Definition at line 123 of file SVHWrapper.h.

◆ m_home_service_all

ros::ServiceServer SVHWrapper::m_home_service_all
private

Definition at line 131 of file SVHWrapper.h.

◆ m_home_service_joint_names

ros::ServiceServer SVHWrapper::m_home_service_joint_names
private

Definition at line 132 of file SVHWrapper.h.

◆ 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

ros::NodeHandle SVHWrapper::m_priv_nh
private

private node handle

Definition at line 82 of file SVHWrapper.h.

◆ 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

ros::ServiceServer SVHWrapper::m_setAllForceLimits_srv
private

Definition at line 133 of file SVHWrapper.h.

◆ m_setForceLimitById_srv

ros::ServiceServer SVHWrapper::m_setForceLimitById_srv
private

Definition at line 134 of file SVHWrapper.h.

◆ m_svh_diagnostics

std::shared_ptr<SVHDiagnostics> SVHWrapper::m_svh_diagnostics
private

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:


schunk_svh_driver
Author(s): Georg Heppner , Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55